diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp index baa7378..8df1551 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp @@ -27,188 +27,107 @@ #include "rosidl_typesupport_introspection_c/field_types.h" #include "rosidl_typesupport_introspection_c/message_introspection.h" +#include "./iceoryx_serialization_common.hpp" + namespace rmw_iceoryx_cpp { namespace details_c { -const char * deserialize( - const char * serialized_msg, - const rosidl_typesupport_introspection_c__MessageMembers * members, - void * ros_message); - -std::pair load_array_size(const char * serialized_msg) -{ - // This is 64 bit aligned - // REVIEW: Please discuss - const uint32_t array_check = *reinterpret_cast(serialized_msg); - serialized_msg += sizeof(array_check); - const uint32_t array_size = *reinterpret_cast(serialized_msg); - serialized_msg += sizeof(array_size); - - if (array_check != 101) { - std::cerr << "deserialization failure: array size is " << array_size << - " and check failed! (" << array_check << - ")" << std::endl; - } - return std::make_pair(serialized_msg, array_size); -} - -inline std::pair get_submessage_array_c( - const rosidl_typesupport_introspection_c__MessageMember * member, +template< + class T, + size_t SizeT = sizeof(T) +> +const char * deserialize_element( const char * serialized_msg, - void * ros_message_field, - void * & subros_message, - size_t sub_members_size) -{ - (void)member; - uint32_t array_elements = 0; - std::tie(serialized_msg, array_elements) = load_array_size(serialized_msg); - - auto data_array = - const_cast(reinterpret_cast(ros_message_field)); - - data_array->data = static_cast(calloc(array_elements, sub_members_size)); - data_array->capacity = array_elements; - data_array->size = array_elements; - - subros_message = reinterpret_cast(data_array->data); - - return std::make_pair(serialized_msg, array_elements); -} - -template -const char * copy_payload_array_c(const char * serialized_msg, void * ros_message_field) + void * ros_message_field) { - uint32_t size = sizeof(T); - uint32_t array_size = 0; - std::tie(serialized_msg, array_size) = load_array_size(serialized_msg); - - uint32_t char_size = size * array_size; - - auto data_array = - const_cast(reinterpret_cast(ros_message_field)); - - data_array->data = static_cast(calloc(array_size, size)); - data_array->capacity = array_size; + T * data = reinterpret_cast(ros_message_field); + memcpy(data, serialized_msg, SizeT); + serialized_msg += SizeT; - memcpy(data_array->data, serialized_msg, char_size); - serialized_msg += char_size; - - data_array->capacity = array_size; - data_array->size = array_size; return serialized_msg; } template<> -const char * copy_payload_array_c( +const char * deserialize_element( const char * serialized_msg, void * ros_message_field) { - serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field); - - auto data_array = - const_cast(reinterpret_cast(ros_message_field)); - - // Set size of string to \0 - auto array_size = strlen((const char *) const_cast(data_array->data)); - data_array->size = array_size; + uint32_t string_size = 0; + std::tie(serialized_msg, string_size) = pop_sequence_size(serialized_msg); + auto string = reinterpret_cast(ros_message_field); + // valgrind reports a memory leak here + rosidl_runtime_c__String__assignn(string, serialized_msg, string_size); + serialized_msg += string_size; return serialized_msg; } template -const char * copy_payload_fixed_array_c( - const char * serialized_msg, void * ros_message_field, +const char * deserialize_array( + const char * serialized_msg, + void * ros_message_field, uint32_t size) { - T * ros_message_field_data = reinterpret_cast *>(ros_message_field)->data(); - auto char_size = size * sizeof(T); - memcpy(ros_message_field_data, serialized_msg, char_size); - serialized_msg += char_size; - + auto array = reinterpret_cast(ros_message_field); + for (size_t i = 0; i < size; ++i) { + auto data = reinterpret_cast(&array[i]); + serialized_msg = deserialize_element(serialized_msg, data); + } return serialized_msg; } -template -const char * copy_payload_c( - const rosidl_typesupport_introspection_c__MessageMember * member, - const char * serialized_msg, void * ros_message_field) +template< + class T, + size_t SizeT = sizeof(T) +> +const char * deserialize_sequence(const char * serialized_msg, void * ros_message_field) { - if (!member->is_array_) { - uint32_t size = sizeof(T); - T * data = reinterpret_cast(ros_message_field); - memcpy(data, serialized_msg, size); - serialized_msg += size; - } else { - if (member->array_size_ > 0 && !member->is_upper_bound_) { - serialized_msg = copy_payload_fixed_array_c( - serialized_msg, ros_message_field, - member->array_size_); - } else { - serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field); - } + uint32_t array_size = 0; + std::tie(serialized_msg, array_size) = pop_sequence_size(serialized_msg); + + if (array_size > 0) { + auto sequence = reinterpret_cast::type *>(ros_message_field); + sequence->data = static_cast(calloc(array_size, SizeT)); + sequence->size = array_size; + sequence->capacity = array_size; + + return deserialize_array(serialized_msg, sequence->data, array_size); } return serialized_msg; } template<> -const char * copy_payload_c( - const rosidl_typesupport_introspection_c__MessageMember * member, const char * serialized_msg, - void * ros_message_field) +const char * deserialize_sequence(const char * serialized_msg, void * ros_message_field) { - if (!member->is_array_) { - serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field); - } else { - if (member->array_size_ > 0 && !member->is_upper_bound_) { - std::string * ros_message_field_data = - reinterpret_cast *>(ros_message_field)->data(); - for (auto i = 0u; i < member->array_size_; ++i) { - serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field_data); - } - } else { - uint32_t array_size = 0; - std::tie(serialized_msg, array_size) = load_array_size(serialized_msg); - for (uint32_t i = 0; i < array_size; ++i) { - serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field); - } - } + uint32_t array_size = 0; + std::tie(serialized_msg, array_size) = pop_sequence_size(serialized_msg); + + if (array_size > 0) { + auto sequence = reinterpret_cast(ros_message_field); + sequence->data = static_cast(calloc(array_size, sizeof(char))); + sequence->size = array_size; + sequence->capacity = array_size; + + return deserialize_array(serialized_msg, sequence->data, array_size); } return serialized_msg; } -const char * copy_payload_c_ros_message( - const rosidl_typesupport_introspection_c__MessageMember * member, const char * serialized_msg, - void * ros_message_field) +template +const char * deserialize_message_field( + const rosidl_typesupport_introspection_c__MessageMember * member, + const char * serialized_msg, void * ros_message_field) { - auto sub_members = - (const rosidl_typesupport_introspection_c__MessageMembers *)member->members_->data; + debug_log("deserializing %s\n", member->name_); if (!member->is_array_) { - serialized_msg = deserialize(serialized_msg, sub_members, ros_message_field); + return deserialize_element(serialized_msg, ros_message_field); + } else if (member->array_size_ > 0 && !member->is_upper_bound_) { + return deserialize_array(serialized_msg, ros_message_field, member->array_size_); } else { - void * subros_message = nullptr; - size_t array_elememts = 0; - size_t sub_members_size = sub_members->size_of_; - - if (member->array_size_ && !member->is_upper_bound_) { - subros_message = ros_message_field; - array_elememts = member->array_size_; - } else { - std::tie(serialized_msg, array_elememts) = get_submessage_array_c( - member, serialized_msg, ros_message_field, subros_message, sub_members_size); - } - for (size_t index = 0; index < array_elememts; ++index) { - serialized_msg = deserialize(serialized_msg, sub_members, subros_message); - subros_message = static_cast(subros_message) + sub_members_size; - } + return deserialize_sequence(serialized_msg, ros_message_field); } - return serialized_msg; } const char * deserialize( @@ -221,45 +140,76 @@ const char * deserialize( char * ros_message_field = static_cast(ros_message) + member->offset_; switch (member->type_id_) { case ::rosidl_typesupport_introspection_c__ROS_TYPE_BOOL: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_BYTE: case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT8: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_CHAR: case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT8: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT32: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT64: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT16: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT16: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT32: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT32: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT64: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT64: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING: - serialized_msg = copy_payload_c(member, serialized_msg, ros_message_field); + serialized_msg = deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: - serialized_msg = copy_payload_c_ros_message(member, serialized_msg, ros_message_field); + { + auto sub_members = + (const rosidl_typesupport_introspection_c__MessageMembers *)member->members_->data; + + void * subros_message = nullptr; + size_t sequence_size = 0; + size_t sub_members_size = sub_members->size_of_; + // It's a single message + if (!member->is_array_) { + subros_message = ros_message_field; + sequence_size = 1; + } else if (member->array_size_ > 0 && !member->is_upper_bound_) { + subros_message = ros_message_field; + sequence_size = member->array_size_; + } else { + debug_log("deserializing ROS message %s\n", member->name_); + + std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); + + auto sequence = + const_cast(reinterpret_cast(ros_message_field)); + + subros_message = reinterpret_cast(sequence->data); + } + + for (size_t index = 0; index < sequence_size; ++index) { + serialized_msg = deserialize(serialized_msg, sub_members, subros_message); + subros_message = static_cast(subros_message) + sub_members_size; + } + } break; default: throw std::runtime_error("unknown type"); diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp index 380b593..1d71afc 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp @@ -123,7 +123,7 @@ const char * deserialize_sequence( const char * serialized_msg, void * ros_message_field) { uint32_t sequence_size = 0; - std::tie(serialized_msg, sequence_size) = pop_array_size(serialized_msg); + std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); if (sequence_size > 0) { debug_log("deserializigng data sequence of size %zu\n", sequence_size); auto sequence = reinterpret_cast(ros_message_field); @@ -142,7 +142,7 @@ const char * deserialize_sequence>( const char * serialized_msg, void * ros_message_field) { uint32_t sequence_size = 0; - std::tie(serialized_msg, sequence_size) = pop_array_size(serialized_msg); + std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); if (sequence_size > 0) { auto sequence = reinterpret_cast *>(ros_message_field); debug_log("deserializing bool sequence of size %zu\n", sequence_size); @@ -163,7 +163,7 @@ const char * deserialize_sequence( const char * serialized_msg, void * ros_message_field) { uint32_t sequence_size = 0; - std::tie(serialized_msg, sequence_size) = pop_array_size(serialized_msg); + std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); if (sequence_size > 0) { debug_log("deserializing wstring sequence of size %zu\n", sequence_size); auto sequence = reinterpret_cast(ros_message_field); @@ -249,21 +249,30 @@ const char * deserialize( { auto sub_members = (const rosidl_typesupport_introspection_cpp::MessageMembers *)member->members_->data; + + void * subros_message = nullptr; + size_t sequence_size = 0; + size_t sub_members_size = sub_members->size_of_; + // It's a single message if (!member->is_array_) { - serialized_msg = deserialize(serialized_msg, sub_members, ros_message_field); + subros_message = ros_message_field; + sequence_size = 1; + } else if (member->array_size_ > 0 && !member->is_upper_bound_) { + subros_message = ros_message_field; + sequence_size = member->array_size_; } else { debug_log("deserializing ROS message %s\n", member->name_); - void * subros_message = nullptr; - size_t array_elememts = 0; - size_t sub_members_size = sub_members->size_of_; - std::tie(serialized_msg, array_elememts) = get_submessage_vector_cpp( - member, serialized_msg, ros_message_field, subros_message, sub_members_size); + std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); + + auto sequence = reinterpret_cast *>(ros_message_field); + sequence->resize(sequence_size * sub_members_size); + subros_message = reinterpret_cast(sequence->data()); + } - for (size_t index = 0; index < array_elememts; ++index) { - serialized_msg = deserialize(serialized_msg, sub_members, subros_message); - subros_message = static_cast(subros_message) + sub_members_size; - } + for (size_t index = 0; index < sequence_size; ++index) { + serialized_msg = deserialize(serialized_msg, sub_members, subros_message); + subros_message = static_cast(subros_message) + sub_members_size; } } break; diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp index c31c57e..c9be35e 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp @@ -18,6 +18,9 @@ #include #include +namespace rmw_iceoryx_cpp +{ + #define DEBUG_LOG 0 static inline void debug_log(const char * format, ...) @@ -33,7 +36,7 @@ static inline void debug_log(const char * format, ...) #endif } -inline void store_sequence_size(std::vector & payloadVector, uint32_t array_size) +inline void push_sequence_size(std::vector & payloadVector, uint32_t array_size) { const uint32_t check = 101; const char * sizePtr = reinterpret_cast(&array_size); @@ -42,7 +45,7 @@ inline void store_sequence_size(std::vector & payloadVector, uint32_t arra payloadVector.insert(payloadVector.end(), sizePtr, sizePtr + sizeof(array_size)); } -inline std::pair pop_array_size(const char * serialized_msg) +inline std::pair pop_sequence_size(const char * serialized_msg) { // This is 64 bit aligned // REVIEW: Please discuss @@ -57,25 +60,93 @@ inline std::pair pop_array_size(const char * serialized_ return std::make_pair(serialized_msg, array_size); } -// FIXME: Use proper templating here! + add allocator handling -inline std::pair get_submessage_vector_cpp( - const rosidl_typesupport_introspection_cpp::MessageMember * member, - const char * serialized_msg, - char * ros_message_field, - void * & subros_message, - size_t sub_members_size) -{ - if (member->array_size_ > 0 && !member->is_upper_bound_) { - size_t array_elements = member->array_size_; - subros_message = ros_message_field; - return std::make_pair(serialized_msg, array_elements); - } +namespace details_c +{ +namespace traits +{ - uint32_t vector_elements = 0; - std::tie(serialized_msg, vector_elements) = pop_array_size(serialized_msg); - auto vector = reinterpret_cast *>(ros_message_field); +template +struct sequence_type; - vector->resize(vector_elements * sub_members_size); - subros_message = reinterpret_cast(vector->data()); - return std::make_pair(serialized_msg, vector_elements); -} +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__boolean__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__char__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__float__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__double__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__int8__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__uint8__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__int16__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__uint16__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__int32__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__uint32__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__int64__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__uint64__Sequence; +}; + +template<> +struct sequence_type +{ + using type = rosidl_runtime_c__String__Sequence; +}; + +} // namespace traits +} // namespace details_c + +} // namespace rmw_iceoryx_cpp diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp index 38f5153..5e8ec70 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp @@ -42,7 +42,6 @@ void serialize( if (ts_cpp != nullptr) { auto members = static_cast(ts_cpp->data); - fprintf(stderr, "let's go with %s\n", members->message_name_); rmw_iceoryx_cpp::details_cpp::serialize(ros_message, members, payload_vector); } diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp index a10bac0..784b516 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp @@ -24,146 +24,90 @@ #include "rosidl_typesupport_introspection_c/field_types.h" #include "rosidl_typesupport_introspection_c/message_introspection.h" -// forward declarations for recursion -#include "iceoryx_serialize_typesupport_c.hpp" +#include "./iceoryx_serialization_common.hpp" namespace rmw_iceoryx_cpp { namespace details_c { -void serialize( - const void * ros_message, - const rosidl_typesupport_introspection_c__MessageMembers * members, - std::vector & payloadVector); +template< + class T, + size_t SizeT = sizeof(T) +> +void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field); + +template< + class T, + size_t SizeT = sizeof(T) +> +void serialize_element( + std::vector & serialized_msg, + const char * ros_message_field) +{ + debug_log("serializing data element of %u bytes\n", SizeT); + serialized_msg.insert(serialized_msg.end(), ros_message_field, ros_message_field + SizeT); +} -void store_array_size(std::vector & payloadVector, uint32_t array_size) +template<> +void serialize_element( + std::vector & serialized_msg, + const char * ros_message_field) { - const uint32_t check = 101; - const char * sizePtr = reinterpret_cast(&array_size); - const char * checkPtr = reinterpret_cast(&check); - payloadVector.insert(payloadVector.end(), checkPtr, checkPtr + sizeof(check)); - payloadVector.insert(payloadVector.end(), sizePtr, sizePtr + sizeof(array_size)); + auto string = reinterpret_cast(ros_message_field); + push_sequence_size(serialized_msg, string->size); + serialized_msg.insert(serialized_msg.end(), string->data, string->data + string->size); } -size_t get_array_elememts_and_assign_ros_message_field_c( - const rosidl_typesupport_introspection_c__MessageMember * member, +template< + class T, + size_t SizeT = sizeof(T) +> +void serialize_array( + std::vector & serialized_msg, const void * ros_message_field, - void * & subros_message -) + uint32_t size) { - auto data_array = reinterpret_cast(ros_message_field); - uint32_t array_size = data_array->size; - - if (member->is_upper_bound_ && array_size > member->array_size_) { - throw std::runtime_error("vector overcomes the maximum length"); + auto array = reinterpret_cast(ros_message_field); + for (size_t i = 0; i < size; ++i) { + auto data = reinterpret_cast(&array[i]); + serialize_element(serialized_msg, data); } - // create ptr to content of vector to enable recursion - subros_message = const_cast(reinterpret_cast(data_array->data)); - return array_size; } -template -void copy_data_array_c(std::vector & payloadVector, const void * ros_message_field) +template< + class T, + size_t SizeT = sizeof(T) +> +void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field) { - auto data_array = reinterpret_cast(ros_message_field); - uint32_t array_size = data_array->size; - uint32_t size = sizeof(T) * array_size; - - store_array_size(payloadVector, array_size); + auto sequence = reinterpret_cast::type *>(ros_message_field); + uint32_t sequence_size = sequence->size; - const char * arrayPtr = reinterpret_cast(data_array->data); - payloadVector.insert(payloadVector.end(), arrayPtr, arrayPtr + size); -} + push_sequence_size(serialized_msg, sequence_size); -template -void copy_data_fixed_array( - std::vector & payloadVector, const void * ros_message_field, - uint32_t size) -{ - auto fixed_array = reinterpret_cast *>(ros_message_field); - auto dataPtr = reinterpret_cast(fixed_array->data()); - payloadVector.insert(payloadVector.end(), dataPtr, dataPtr + size * sizeof(T)); + serialize_array(serialized_msg, sequence->data, sequence_size); } template -void copy_data_c( - const rosidl_typesupport_introspection_c__MessageMember * member, - std::vector & payloadVector, const char * ros_message_field) -{ - if (!member->is_array_) { - uint32_t size = sizeof(T); - payloadVector.insert(payloadVector.end(), ros_message_field, ros_message_field + size); - } else { - if (member->array_size_ > 0 && !member->is_upper_bound_) { - copy_data_fixed_array(payloadVector, ros_message_field, member->array_size_); - } else { - copy_data_array_c(payloadVector, ros_message_field); - } - } -} - -template<> -void copy_data_c( +void serialize_message_field( const rosidl_typesupport_introspection_c__MessageMember * member, - std::vector & payloadVector, const char * ros_message_field) + std::vector & serialized_msg, const char * ros_message_field) { + debug_log("serializing message field %s\n", member->name_); if (!member->is_array_) { - copy_data_array_c(payloadVector, ros_message_field); + serialize_element(serialized_msg, ros_message_field); + } else if (member->array_size_ > 0 && !member->is_upper_bound_) { + serialize_array(serialized_msg, ros_message_field, member->array_size_); } else { - if (member->array_size_ > 0 && !member->is_upper_bound_) { - auto data = reinterpret_cast *>(ros_message_field); - auto array_size = static_cast(member->array_size_); - for (auto i = 0u; i < array_size; ++i) { - std::string data_element = data->data()[i]; - copy_data_array_c(payloadVector, data_element.c_str()); - } - } else { - auto data_array = - reinterpret_cast(ros_message_field); - uint32_t array_size = data_array->size; // number of strings in the array - - store_array_size(payloadVector, array_size); - - auto dataPtr = reinterpret_cast(data_array->data); - - for (uint32_t i = 0; i < array_size; ++i) { - copy_data_array_c(payloadVector, dataPtr); - dataPtr += sizeof(std::string); - } - } - } -} - -void copy_data_c_ros_message( - const rosidl_typesupport_introspection_c__MessageMember * member, - std::vector & payloadVector, const char * ros_message_field) -{ - auto sub_members = - static_cast(member->members_->data); - if (!member->is_array_) { - serialize(ros_message_field, sub_members, payloadVector); - } else { - void * subros_message = nullptr; - size_t sub_members_size = sub_members->size_of_; - size_t array_elememts = get_array_elememts_and_assign_ros_message_field_c( - member, - ros_message_field, - subros_message); - - store_array_size(payloadVector, array_elememts); - - for (size_t index = 0; index < array_elememts; ++index) { - serialize(subros_message, sub_members, payloadVector); - subros_message = static_cast(subros_message) + sub_members_size; - } + serialize_sequence(serialized_msg, ros_message_field); } } void serialize( const void * ros_message, const rosidl_typesupport_introspection_c__MessageMembers * members, - std::vector & payloadVector) + std::vector & serialized_msg) { assert(members); assert(ros_message); @@ -173,46 +117,82 @@ void serialize( const char * ros_message_field = static_cast(ros_message) + member->offset_; switch (member->type_id_) { case ::rosidl_typesupport_introspection_c__ROS_TYPE_BOOL: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_BYTE: case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT8: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_CHAR: case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT8: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT32: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT64: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT16: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT16: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT32: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT32: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT64: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT64: - copy_data_c(member, payloadVector, ros_message_field); + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING: - copy_data_c(member, payloadVector, ros_message_field); - + serialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: - copy_data_c_ros_message(member, payloadVector, ros_message_field); + { + // Iterate recursively over the complex ROS messages + auto sub_members = + static_cast(member->members_->data); + + const void * subros_message = nullptr; + size_t sequence_size = 0; + size_t sub_members_size = sub_members->size_of_; + // It's a single message + if (!member->is_array_) { + subros_message = ros_message_field; + sequence_size = 1; + // It's a fixed size array of messages + } else if (member->array_size_ > 0 && !member->is_upper_bound_) { + subros_message = ros_message_field; + sequence_size = member->array_size_; + // It's a dynamic sequence of messages + } else { + // Cast current ros_message_field ptr as vector "definition" + auto vector = reinterpret_cast(ros_message_field); + // Vector size points to content of vector and returns number of bytes + // submembersize is the size of one element in the vector (it is provided by type support) + sequence_size = vector->size / sub_members_size; + if (member->is_upper_bound_ && sequence_size > member->array_size_) { + throw std::runtime_error("vector overcomes the maximum length"); + } + // create ptr to content of vector to enable recursion + subros_message = reinterpret_cast(vector->data); + // store the number of elements + push_sequence_size(serialized_msg, sequence_size); + } + + debug_log("serializing message field %s\n", member->name_); + for (auto index = 0u; index < sequence_size; ++index) { + serialize(subros_message, sub_members, serialized_msg); + subros_message = static_cast(subros_message) + sub_members_size; + } + } break; default: throw std::runtime_error("unknown type"); diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp index 0747d52..9918458 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp @@ -118,7 +118,7 @@ void serialize_sequence(std::vector & serialized_msg, const void * ros_mes uint32_t size = sequence->size(); debug_log("serializing data sequence of size %u\n", size); - store_sequence_size(serialized_msg, size); + push_sequence_size(serialized_msg, size); for (const T & t : *sequence) { const char * data = reinterpret_cast(&t); serialize_element(serialized_msg, data); @@ -224,7 +224,7 @@ void serialize( // create ptr to content of vector to enable recursion subros_message = reinterpret_cast(vector->data()); // store the number of elements - store_sequence_size(serialized_msg, sequence_size); + push_sequence_size(serialized_msg, sequence_size); } debug_log("serializing message field %s\n", member->name_); diff --git a/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp b/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp index 9224ad3..5e3a21a 100644 --- a/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp +++ b/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp @@ -194,29 +194,29 @@ TEST(SerializationTests, c_flip_flop_serialize_defaults) flip_flop_serialization(std::bind(&get_messages_defaults_c), ts); } -//TEST(SerializationTests, c_flip_flop_serialize_strings) -//{ -// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); -// flip_flop_serialization(std::bind(&get_messages_strings_c), ts); -//} +TEST(SerializationTests, c_flip_flop_serialize_strings) +{ + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + flip_flop_serialization(std::bind(&get_messages_strings_c), ts); +} -//TEST(SerializationTests, c_flip_flop_serialize_arrays) -//{ -// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Arrays); -// flip_flop_serialization(std::bind(&get_messages_arrays_c), ts); -//} +TEST(SerializationTests, c_flip_flop_serialize_arrays) +{ + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Arrays); + flip_flop_serialization(std::bind(&get_messages_arrays_c), ts); +} -//TEST(SerializationTests, c_flip_flop_serialize_unbounded_sequences) -//{ -// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, UnboundedSequences); -// flip_flop_serialization(std::bind(&get_messages_unbounded_sequences_c), ts); -//} -// -//TEST(SerializationTests, c_flip_flop_serialize_bounded_sequences) -//{ -// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BoundedSequences); -// flip_flop_serialization(std::bind(&get_messages_bounded_sequences_c), ts); -//} +TEST(SerializationTests, c_flip_flop_serialize_unbounded_sequences) +{ + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, UnboundedSequences); + flip_flop_serialization(std::bind(&get_messages_unbounded_sequences_c), ts); +} + +TEST(SerializationTests, c_flip_flop_serialize_bounded_sequences) +{ + auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BoundedSequences); + flip_flop_serialization(std::bind(&get_messages_bounded_sequences_c), ts); +} TEST(SerializationTests, c_flip_flop_serialize_nested) {