Skip to content

Commit

Permalink
chore: complete the 1st version
Browse files Browse the repository at this point in the history
  • Loading branch information
YuanYuYuan authored and imstevenpmwork committed Aug 8, 2024
1 parent 2a828f7 commit c3462f3
Show file tree
Hide file tree
Showing 19 changed files with 2,259 additions and 2,350 deletions.
149 changes: 108 additions & 41 deletions rmw_zenoh_cpp/src/detail/attachment_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,85 +12,152 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <cstdio>
#include <zenoh.h>

#include <cstdlib>
#include <cstring>
#include <string>
#include <zenoh_macros.h>

#include "rmw/types.h"

#include "logging_macros.hpp"

#include "attachment_helpers.hpp"

namespace rmw_zenoh_cpp
{
bool get_gid_from_attachment(
const z_attachment_t * const attachment, uint8_t gid[RMW_GID_STORAGE_SIZE])
{
if (!z_check(*attachment)) {
namespace rmw_zenoh_cpp {

bool create_attachment_iter(z_owned_bytes_t *kv_pair, void *context) {
attachement_context_t *ctx = (attachement_context_t *)context;
z_owned_bytes_t k, v;

if (ctx->idx == 0) {
z_bytes_serialize_from_str(&k, "sequence_number");
z_bytes_serialize_from_int64(&v, ctx->data->sequence_number);
} else if (ctx->idx == 1) {
z_bytes_serialize_from_str(&k, "source_timestamp");
z_bytes_serialize_from_int64(&v, ctx->data->source_timestamp);
} else if (ctx->idx == 2) {
z_bytes_serialize_from_str(&k, "source_gid");
z_bytes_serialize_from_slice_copy(&v, ctx->data->source_gid,
RMW_GID_STORAGE_SIZE);
} else {
return false;
}

z_bytes_t index = z_attachment_get(*attachment, z_bytes_new("source_gid"));
if (!z_check(index)) {
z_bytes_serialize_from_pair(kv_pair, z_move(k), z_move(v));
ctx->idx += 1;
return true;
}

z_error_t attachement_data_t::serialize_to_zbytes(z_owned_bytes_t *attachment) {
attachement_context_t context = attachement_context_t(this);
return z_bytes_serialize_from_iter(attachment, create_attachment_iter,
(void *)&context);
}

bool get_attachment(const z_loaned_bytes_t *const attachment,
const std::string &key, z_owned_bytes_t *val) {
if (z_bytes_is_empty(attachment)) {
return false;
}

if (index.len != RMW_GID_STORAGE_SIZE) {
z_bytes_iterator_t iter = z_bytes_get_iterator(attachment);
z_owned_bytes_t pair, key_;
bool found = false;

while (z_bytes_iterator_next(&iter, &pair)) {
z_bytes_deserialize_into_pair(z_loan(pair), &key_, val);
z_owned_string_t key_string;
z_bytes_deserialize_into_string(z_loan(key_), &key_string);

char dbg_info[120];
sprintf(dbg_info, "Given key: %s, found: %s", key.c_str(),
z_string_data(z_loan(key_string)));
sprintf(dbg_info, "Given key: %s, found: %.*s", key.c_str(),
(int)z_string_len(z_loan(key_string)),
z_string_data(z_loan(key_string)));

std::string found_key;
found_key.assign(z_string_data(z_loan(key_string)), z_string_len(z_loan(key_string)));
if (found_key == key) {
// if (strcmp(z_string_data(z_loan(key_string)), key.c_str()) == 0) {
found = true;
}

z_drop(z_move(pair));
z_drop(z_move(key_));
z_drop(z_move(key_string));

if (found) {
break;
}
}

if (!found) {
return false;
}

memcpy(gid, index.start, index.len);
if (z_bytes_is_empty(z_loan(*val))) {
return false;
}

return true;
}

int64_t get_int64_from_attachment(
const z_attachment_t * const attachment, const std::string & name)
{
if (!z_check(*attachment)) {
// A valid request must have had an attachment
return -1;
bool get_gid_from_attachment(const z_loaned_bytes_t *const attachment,
uint8_t gid[RMW_GID_STORAGE_SIZE]) {

if (z_bytes_is_empty(attachment)) {
return false;
}

z_bytes_t index = z_attachment_get(*attachment, z_bytes_new(name.c_str()));
if (!z_check(index)) {
return -1;
z_owned_bytes_t val;
if (!get_attachment(attachment, "source_gid", &val)) {
return false;
}

if (index.len < 1) {
return -1;
z_owned_slice_t slice;
z_bytes_deserialize_into_slice(z_loan(val), &slice);
if (z_slice_len(z_loan(slice)) != RMW_GID_STORAGE_SIZE) {
RMW_ZENOH_LOG_ERROR_NAMED("rmw_zenoh_cpp", "GID length mismatched.")
return false;
}
memcpy(gid, z_slice_data(z_loan(slice)), z_slice_len(z_loan(slice)));

if (index.len > 19) {
// The number was larger than we expected
z_drop(z_move(val));
z_drop(z_move(slice));

return true;
}

int64_t get_int64_from_attachment(const z_loaned_bytes_t *const attachment,
const std::string &name) {
// A valid request must have had an attachment
if (z_bytes_is_empty(attachment)) {
return -1;
}

// The largest possible int64_t number is INT64_MAX, i.e. 9223372036854775807.
// That is 19 characters long, plus one for the trailing \0, means we need 20 bytes.
char int64_str[20];
// TODO(yuyuan): This key should be specific
z_owned_bytes_t val;
if (!get_attachment(attachment, name, &val)) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp", "Failed to deserialize int64 from the attachment.")
return false;
}

memcpy(int64_str, index.start, index.len);
int64_str[index.len] = '\0';
int64_t num;
if (z_bytes_deserialize_into_int64(z_loan(val), &num)) {
return -1;
}

errno = 0;
char * endptr;
int64_t num = strtol(int64_str, &endptr, 10);
if (num == 0) {
// This is an error regardless; the client should never send this
return -1;
} else if (endptr == int64_str) {
// No values were converted, this is an error
return -1;
} else if (*endptr != '\0') {
// There was junk after the number
return -1;
} else if (errno != 0) {
// Some other error occurred, which may include overflow or underflow
return -1;
}

return num;
}
} // namespace rmw_zenoh_cpp

} // namespace rmw_zenoh_cpp
43 changes: 35 additions & 8 deletions rmw_zenoh_cpp/src/detail/attachment_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,13 +21,40 @@

#include "rmw/types.h"

namespace rmw_zenoh_cpp
{
bool get_gid_from_attachment(
const z_attachment_t * const attachment, uint8_t gid[RMW_GID_STORAGE_SIZE]);
namespace rmw_zenoh_cpp {

int64_t get_int64_from_attachment(
const z_attachment_t * const attachment, const std::string & name);
} // namespace rmw_zenoh_cpp
class attachement_data_t final {
public:
int64_t sequence_number;
int64_t source_timestamp;
uint8_t source_gid[RMW_GID_STORAGE_SIZE];
attachement_data_t(const int64_t _sequence_number,
const int64_t _source_timestamp,
const uint8_t _source_gid[RMW_GID_STORAGE_SIZE]) {
sequence_number = _sequence_number;
source_timestamp = _source_timestamp;
memcpy(source_gid, _source_gid, RMW_GID_STORAGE_SIZE);
}
z_error_t serialize_to_zbytes(z_owned_bytes_t *);
};

#endif // DETAIL__ATTACHMENT_HELPERS_HPP_
class attachement_context_t final {
public:
const attachement_data_t *data;
int length = 3;
int idx = 0;

attachement_context_t(const attachement_data_t *_data) : data(_data) {}
};

bool get_attachment(const z_loaned_bytes_t *const attachment,
const std::string &key, z_owned_bytes_t *val);

bool get_gid_from_attachment(const z_loaned_bytes_t *const attachment,
uint8_t gid[RMW_GID_STORAGE_SIZE]);

int64_t get_int64_from_attachment(const z_loaned_bytes_t *const attachment,
const std::string &name);
} // namespace rmw_zenoh_cpp

#endif // DETAIL__ATTACHMENT_HELPERS_HPP_
1 change: 0 additions & 1 deletion rmw_zenoh_cpp/src/detail/graph_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <memory>
#include <mutex>
#include <optional>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
Expand Down
5 changes: 1 addition & 4 deletions rmw_zenoh_cpp/src/detail/graph_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 +22,14 @@
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <vector>

#include "event.hpp"
#include "liveliness_utils.hpp"
#include "ordered_map.hpp"

#include "rcutils/allocator.h"
#include "rcutils/types.h"

#include "rmw/rmw.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/topic_endpoint_info_array.h"
#include "rmw/names_and_types.h"


Expand Down
1 change: 0 additions & 1 deletion rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <functional>
#include <optional>
#include <sstream>
#include <stdexcept>
#include <string>
#include <unordered_map>
#include <utility>
Expand Down
1 change: 0 additions & 1 deletion rmw_zenoh_cpp/src/detail/liveliness_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <memory>
#include <optional>
#include <string>
#include <vector>

#include "rmw/types.h"

Expand Down
1 change: 1 addition & 0 deletions rmw_zenoh_cpp/src/detail/logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,4 +63,5 @@ void Logger::log_named(
);
}
}

} // namespace rmw_zenoh_cpp
Loading

0 comments on commit c3462f3

Please sign in to comment.