diff --git a/rosidl_typesupport_fastrtps_c/resource/msg__type_support_c.cpp.em b/rosidl_typesupport_fastrtps_c/resource/msg__type_support_c.cpp.em index 8a67a28..09f561f 100644 --- a/rosidl_typesupport_fastrtps_c/resource/msg__type_support_c.cpp.em +++ b/rosidl_typesupport_fastrtps_c/resource/msg__type_support_c.cpp.em @@ -612,6 +612,344 @@ if isinstance(type_, AbstractNestedType): return current_alignment - initial_alignment; } +size_t +ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__max_serialized_key_size( + size_t initial_alignment, + bool & is_unbounded) +{ +@[ if message.structure.has_any_member_with_annotation('key') ]@ + size_t current_alignment = initial_alignment; + + const size_t padding = 4; + const size_t wchar_size = 4; + (void)padding; + (void)wchar_size; + +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // member: @(member.name) + { +@[ if isinstance(member.type, AbstractNestedType)]@ +@[ if isinstance(member.type, Array)]@ + size_t array_size = @(member.type.size); +@[ elif isinstance(member.type, BoundedSequence)]@ + size_t array_size = @(member.type.maximum_size); +@[ else]@ + size_t array_size = 0; +@[ end if]@ +@[ if isinstance(member.type, AbstractSequence)]@ + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding); +@[ end if]@ +@[ else]@ + size_t array_size = 1; +@[ end if]@ + +@{ +type_ = member.type +if isinstance(type_, AbstractNestedType): + type_ = type_.value_type +}@ +@[ if isinstance(type_, AbstractGenericString)]@ + is_unbounded = true; + for (size_t index = 0; index < array_size; ++index) { + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if type_.has_maximum_size()]@ +@[ if isinstance(type_, AbstractWString)]@ + wchar_size * +@[ end if]@ + @(type_.maximum_size) + +@[ end if]@ +@[ if isinstance(type_, AbstractWString)]@ + wchar_size * +@[ end if]@ + 1; + } +@[ elif isinstance(type_, BasicType)]@ +@[ if type_.typename in ('boolean', 'octet', 'char', 'uint8', 'int8')]@ + current_alignment += array_size * sizeof(uint8_t); +@[ elif type_.typename in ('wchar', 'int16', 'uint16')]@ + current_alignment += array_size * sizeof(uint16_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint16_t)); +@[ elif type_.typename in ('int32', 'uint32', 'float')]@ + current_alignment += array_size * sizeof(uint32_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint32_t)); +@[ elif type_.typename in ('int64', 'uint64', 'double')]@ + current_alignment += array_size * sizeof(uint64_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint64_t)); +@[ elif type_.typename == 'long double']@ + current_alignment += array_size * sizeof(long double) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(long double)); +@[ end if]@ +@[ else] + for (size_t index = 0; index < array_size; ++index) { + current_alignment += + _@(message.structure.namespaced_type.name)__max_serialized_key_size( + current_alignment, is_unbounded); + } +@[ end if]@ + } +@[end for]@ + + return current_alignment - initial_alignment; +@[ else]@ + static_cast(initial_alignment); + static_cast(is_unbounded); + return static_cast(0); +@[ end if]@ +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__cdr_deserialize_key( + eprosima::fastcdr::Cdr &, + void *) +{ + return false; +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__cdr_serialize_key( + const void * untyped_ros_message, + eprosima::fastcdr::Cdr & cdr) +{ +@[ if message.structure.has_any_member_with_annotation('key') ]@ +if (!untyped_ros_message) { + fprintf(stderr, "ros message handle is null\n"); + return false; + } + const _@(message.structure.namespaced_type.name)__ros_msg_type * ros_message = static_cast(untyped_ros_message); +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // Field name: @(member.name) + { +@{ +type_ = member.type +if isinstance(type_, AbstractNestedType): + type_ = type_.value_type +}@ +@[ if isinstance(type_, NamespacedType)]@ + const message_type_support_callbacks_t * callbacks = + static_cast( + ROSIDL_TYPESUPPORT_INTERFACE__MESSAGE_SYMBOL_NAME( + rosidl_typesupport_fastrtps_c, @(', '.join(type_.namespaced_name())) + )()->data); +@[ end if]@ +@[ if isinstance(member.type, AbstractNestedType)]@ +@[ if isinstance(member.type, Array)]@ + size_t size = @(member.type.size); + auto array_ptr = ros_message->@(member.name); +@[ else]@ + size_t size = ros_message->@(member.name).size; + auto array_ptr = ros_message->@(member.name).data; +@[ if isinstance(member.type, BoundedSequence)]@ + if (size > @(member.type.maximum_size)) { + fprintf(stderr, "array size exceeds upper bound\n"); + return false; + } +@[ end if]@ + cdr << static_cast(size); +@[ end if]@ +@[ if isinstance(member.type.value_type, AbstractString)]@ + for (size_t i = 0; i < size; ++i) { + const rosidl_runtime_c__String * str = &array_ptr[i]; + if (str->capacity == 0 || str->capacity <= str->size) { + fprintf(stderr, "string capacity not greater than size\n"); + return false; + } + if (str->data[str->size] != '\0') { + fprintf(stderr, "string not null-terminated\n"); + return false; + } + cdr << str->data; + } +@[ elif isinstance(member.type.value_type, AbstractWString)]@ + std::wstring wstr; + for (size_t i = 0; i < size; ++i) { + const rosidl_runtime_c__U16String * str = &array_ptr[i]; + if (str->capacity == 0 || str->capacity <= str->size) { + fprintf(stderr, "string capacity not greater than size\n"); + return false; + } + if (str->data[str->size] != u'\0') { + fprintf(stderr, "string not null-terminated\n"); + return false; + } + rosidl_typesupport_fastrtps_c::u16string_to_wstring(*str, wstr); + cdr << wstr; + } +@[ elif isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'wchar']@ + for (size_t i = 0; i < size; ++i) { + if (!callbacks->cdr_serialize( + static_cast(&array_ptr[i]), cdr)) + { + return false; + } + } +@[ elif isinstance(member.type.value_type, BasicType)]@ + cdr.serializeArray(array_ptr, size); +@[ else]@ + for (size_t i = 0; i < size; ++i) { + if (!callbacks->cdr_serialize( + &array_ptr[i], cdr)) + { + return false; + } + } +@[ end if]@ +@[ elif isinstance(member.type, AbstractString)]@ + const rosidl_runtime_c__String * str = &ros_message->@(member.name); + if (str->capacity == 0 || str->capacity <= str->size) { + fprintf(stderr, "string capacity not greater than size\n"); + return false; + } + if (str->data[str->size] != '\0') { + fprintf(stderr, "string not null-terminated\n"); + return false; + } + cdr << str->data; +@[ elif isinstance(member.type, AbstractWString)]@ + std::wstring wstr; + rosidl_typesupport_fastrtps_c::u16string_to_wstring(ros_message->@(member.name), wstr); + cdr << wstr; +@[ elif isinstance(member.type, BasicType) and member.type.typename == 'boolean']@ + cdr << (ros_message->@(member.name) ? true : false); +@[ elif isinstance(member.type, BasicType) and member.type.typename == 'wchar']@ + cdr << static_cast(ros_message->@(member.name)); +@[ elif isinstance(member.type, BasicType)]@ + cdr << ros_message->@(member.name); +@[ else]@ + if (!callbacks->cdr_serialize( + &ros_message->@(member.name), cdr)) + { + return false; + } +@[ end if]@ + } + +@[end for]@ + return true; +@[ else]@ + static_cast(untyped_ros_message); + static_cast(cdr); + return false; +@[ end if]@ +} + +size_t +ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__get_serialized_key_size( + const void * untyped_ros_message, + size_t initial_alignment) +{ +@[ if message.structure.has_any_member_with_annotation('key') ]@ + auto ros_message = + static_cast( + untyped_ros_message); + + size_t current_alignment = initial_alignment; + + const size_t padding = 4; + const size_t wchar_size = 4; + (void)padding; + (void)wchar_size; + +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // Member: @(member.name) +@[ if isinstance(member.type, AbstractNestedType)]@ + { +@[ if isinstance(member.type, Array)]@ + size_t array_size = @(member.type.size); +@[ else]@ + size_t array_size = ros_message->@(member.name).size; +@[ if isinstance(member.type, BoundedSequence)]@ + if (array_size > @(member.type.maximum_size)) { + throw std::runtime_error("array size exceeds upper bound"); + } +@[ end if]@ + + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding); +@[ end if]@ +@[ if isinstance(member.type.value_type, AbstractGenericString)]@ + for (size_t index = 0; index < array_size; ++index) { + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if isinstance(member.type.value_type, AbstractWString)]@ + wchar_size * +@[ end if]@ + (ros_message->@(member.name)[index].size + 1); + } +@[ elif isinstance(member.type.value_type, BasicType)]@ + size_t item_size = sizeof(ros_message->@(member.name)[0]); + current_alignment += array_size * item_size + + eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); +@[ else] + for (size_t index = 0; index < array_size; ++index) { + current_alignment += + _@(message.structure.namespaced_type.name)__get_serialized_key_size( + ros_message->@(member.name)[index], current_alignment); + } +@[ end if]@ + } +@[ else]@ +@[ if isinstance(member.type, AbstractGenericString)]@ + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if isinstance(member.type, AbstractWString)]@ + wchar_size * +@[ end if]@ + (ros_message->@(member.name).size + 1); +@[ elif isinstance(member.type, BasicType)]@ + { + size_t item_size = sizeof(ros_message->@(member.name)); + current_alignment += item_size + + eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); + } +@[ else] + current_alignment += + _@(message.structure.namespaced_type.name)__get_serialized_key_size( + ros_message->@(member.name), current_alignment); +@[ end if]@ +@[ end if]@ +@[end for]@ + + return current_alignment - initial_alignment; +@[ else]@ + static_cast(untyped_ros_message); + static_cast(initial_alignment); + return static_cast(0); +@[ end if]@ +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC_@(package_name) +get_key_type_support_@(message.structure.namespaced_type.name)( + message_type_support_key_callbacks_t * key_callbacks) +{ + std::cout << "Initializing C interface @(message.structure.namespaced_type.name)" << std::endl; +@[ if message.structure.has_any_member_with_annotation('key') ]@ + key_callbacks->max_serialized_key_size = &_@(message.structure.namespaced_type.name)__max_serialized_key_size; + key_callbacks->cdr_deserialize_key = &_@(message.structure.namespaced_type.name)__cdr_deserialize_key; + key_callbacks->cdr_serialize_key = &_@(message.structure.namespaced_type.name)__cdr_serialize_key; + key_callbacks->get_serialized_key_size = &_@(message.structure.namespaced_type.name)__get_serialized_key_size; + return true; +@[ else]@ + static_cast(key_callbacks); + return false; +@[ end if]@ +} + static size_t _@(message.structure.namespaced_type.name)__max_serialized_size(char & bounds_info) { bool full_bounded; @@ -627,6 +965,13 @@ static size_t _@(message.structure.namespaced_type.name)__max_serialized_size(ch return ret_val; } +static bool _@(message.structure.namespaced_type.name)__get_key_type_support(message_type_support_key_callbacks_t * key_callbacks) +{ + bool ret_val; + ret_val = get_key_type_support_@(message.structure.namespaced_type.name)(key_callbacks); + return ret_val; +} + @ @# // Collect the callback functions and provide a function to get the type support struct. @@ -636,7 +981,8 @@ static message_type_support_callbacks_t __callbacks_@(message.structure.namespac _@(message.structure.namespaced_type.name)__cdr_serialize, _@(message.structure.namespaced_type.name)__cdr_deserialize, _@(message.structure.namespaced_type.name)__get_serialized_size, - _@(message.structure.namespaced_type.name)__max_serialized_size + _@(message.structure.namespaced_type.name)__max_serialized_size, + _@(message.structure.namespaced_type.name)__get_key_type_support }; static rosidl_message_type_support_t _@(message.structure.namespaced_type.name)__type_support = { diff --git a/rosidl_typesupport_fastrtps_cpp/include/rosidl_typesupport_fastrtps_cpp/message_type_support.h b/rosidl_typesupport_fastrtps_cpp/include/rosidl_typesupport_fastrtps_cpp/message_type_support.h index 4f37fdb..44d6065 100644 --- a/rosidl_typesupport_fastrtps_cpp/include/rosidl_typesupport_fastrtps_cpp/message_type_support.h +++ b/rosidl_typesupport_fastrtps_cpp/include/rosidl_typesupport_fastrtps_cpp/message_type_support.h @@ -26,6 +26,50 @@ #define ROSIDL_TYPESUPPORT_FASTRTPS_BOUNDED_TYPE 0x01 #define ROSIDL_TYPESUPPORT_FASTRTPS_PLAIN_TYPE 0x03 +// Holds generated methods related with keys +typedef struct message_type_support_key_callbacks_t +{ + /// Callback function for message serialization + /** + * \param[in] untyped_ros_message Type erased pointer to message instance. + * \param [in,out] Serialized FastCDR data object. + * \return true if serialization succeeded, false otherwise. + */ + bool (* cdr_serialize_key)( + const void * untyped_ros_message, + eprosima::fastcdr::Cdr & cdr); + + /// Callback function for message deserialization + /** + * \param [in] Serialized FastCDR data object. + * \param[out] untyped_ros_message Type erased pointer to message instance. + * \return true if deserialization succeeded, false otherwise. + */ + bool (* cdr_deserialize_key)( + eprosima::fastcdr::Cdr & cdr, + void * untyped_ros_message); + + /// Callback function to get size of the key data + /** + * \return The size of the serialized message in bytes. + */ + size_t (* get_serialized_key_size)( + const void * untyped_ros_message, + size_t initial_alignment); + + /// Callback function to determine the maximum size needed for key serialization, + /// which is used for key type support initialization. + /** + * \param [in] initial_alignment Initial alignment to be incrementally calculated. + * \param [in,out] is_unbounded Whether the key has any unbounded member. + * \return The maximum key serialized size, in bytes. + */ + size_t (* max_serialized_key_size)( + size_t initial_aligment, + bool & is_unbounded); + +} message_type_support_key_callbacks_t; + /// Encapsulates the callbacks for getting properties of this rosidl type. /** * These callbacks are implemented in the generated sources. @@ -76,6 +120,16 @@ typedef struct message_type_support_callbacks_t * \return The maximum serialized size, in bytes. */ size_t (* max_serialized_size)(char & bounds_info); + + /// Checks whether the type has keys, filling the incoming argument + /// with the corresponding callbacks when true. + /** + * \param [in,out] key_callbacks Associated struct of key callbacks. + * It is filled only if the type is keyed. + * \return True if the type has a key. + */ + bool (* get_key_type_support)(message_type_support_key_callbacks_t * key_callbacks); + } message_type_support_callbacks_t; #endif // ROSIDL_TYPESUPPORT_FASTRTPS_CPP__MESSAGE_TYPE_SUPPORT_H_ diff --git a/rosidl_typesupport_fastrtps_cpp/resource/msg__rosidl_typesupport_fastrtps_cpp.hpp.em b/rosidl_typesupport_fastrtps_cpp/resource/msg__rosidl_typesupport_fastrtps_cpp.hpp.em index 2b918a4..e96a57a 100644 --- a/rosidl_typesupport_fastrtps_cpp/resource/msg__rosidl_typesupport_fastrtps_cpp.hpp.em +++ b/rosidl_typesupport_fastrtps_cpp/resource/msg__rosidl_typesupport_fastrtps_cpp.hpp.em @@ -49,6 +49,8 @@ header_files = [ @[ end if]@ #include "@(header_file)" @[end for]@ + +struct message_type_support_key_callbacks_t; @[for ns in message.structure.namespaced_type.namespaces]@ namespace @(ns) @@ -83,6 +85,11 @@ max_serialized_size_@(message.structure.namespaced_type.name)( bool & is_plain, size_t current_alignment); +bool +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +get_key_type_support_@(message.structure.namespaced_type.name)( + message_type_support_key_callbacks_t * key_callbacks); + } // namespace typesupport_fastrtps_cpp @[ for ns in reversed(message.structure.namespaced_type.namespaces)]@ diff --git a/rosidl_typesupport_fastrtps_cpp/resource/msg__type_support.cpp.em b/rosidl_typesupport_fastrtps_cpp/resource/msg__type_support.cpp.em index a02d04f..484ff28 100644 --- a/rosidl_typesupport_fastrtps_cpp/resource/msg__type_support.cpp.em +++ b/rosidl_typesupport_fastrtps_cpp/resource/msg__type_support.cpp.em @@ -72,6 +72,9 @@ max_serialized_size_@(type_.name)( bool & full_bounded, bool & is_plain, size_t current_alignment); +bool +get_key_type_support_@(type_.name)( + message_type_support_key_callbacks_t * key_callbacks); } // namespace typesupport_fastrtps_cpp @[ for ns in reversed(type_.namespaces)]@ } // namespace @(ns) @@ -459,6 +462,315 @@ if isinstance(type_, AbstractNestedType): return current_alignment - initial_alignment; } +size_t +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__max_serialized_key_size( + size_t initial_alignment, + bool & is_unbounded) +{ +@[ if message.structure.has_any_member_with_annotation('key') ]@ + size_t current_alignment = initial_alignment; +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // Member: @(member.name) + { +@[ if isinstance(member.type, AbstractNestedType) ]@ +@[ if isinstance(member.type, Array)]@ + size_t array_size = @(member.type.size); +@[ elif isinstance(member.type, BoundedSequence)]@ + size_t array_size = @(member.type.maximum_size); +@[ else]@ + size_t array_size = 0; +@[ end if]@ +@[ if isinstance(member.type, AbstractSequence)]@ + const size_t padding = 4; + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding); +@[ end if]@ +@[ else]@ + size_t array_size = 1; +@[ end if]@ + +@{ +type_ = member.type +if isinstance(type_, AbstractNestedType): + type_ = type_.value_type +}@ +@[ if isinstance(type_, AbstractGenericString)]@ + is_unbounded = true; + const size_t padding = 4; + const size_t wchar_size = 4; + + for (size_t index = 0; index < array_size; ++index) { + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if type_.has_maximum_size()]@ +@[ if isinstance(type_, AbstractWString)]@ + wchar_size * +@[ end if]@ + @(type_.maximum_size) + +@[ end if]@ +@[ if isinstance(type_, AbstractWString)]@ + wchar_size * +@[ end if]@ + 1; + } +@[ elif isinstance(type_, BasicType)]@ +@[ if type_.typename in ('boolean', 'octet', 'char', 'uint8', 'int8')]@ + current_alignment += array_size * sizeof(uint8_t); +@[ elif type_.typename in ('wchar', 'int16', 'uint16')]@ + current_alignment += array_size * sizeof(uint16_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint16_t)); +@[ elif type_.typename in ('int32', 'uint32', 'float')]@ + current_alignment += array_size * sizeof(uint32_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint32_t)); +@[ elif type_.typename in ('int64', 'uint64', 'double')]@ + current_alignment += array_size * sizeof(uint64_t) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(uint64_t)); +@[ elif type_.typename == 'long double']@ + current_alignment += array_size * sizeof(long double) + + eprosima::fastcdr::Cdr::alignment(current_alignment, sizeof(long double)); +@[ end if]@ +@[ else] + for (size_t index = 0; index < array_size; ++index) { + current_alignment += + @('::'.join(type_.namespaces))::typesupport_fastrtps_cpp::_@(message.structure.namespaced_type.name)__max_serialized_key_size( + current_alignment, is_unbounded); + } +@[ end if]@ + } +@[end for]@ + + return current_alignment - initial_alignment; +@[ else]@ + static_cast(initial_alignment); + static_cast(is_unbounded); + return static_cast(0); +@[ end if]@ +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__cdr_deserialize_key( + eprosima::fastcdr::Cdr &, + void *) +{ + return false; +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__cdr_serialize_key( + const void * untyped_ros_message, + eprosima::fastcdr::Cdr & cdr) +{ + +@[ if message.structure.has_any_member_with_annotation('key') ]@ + auto ros_message = + static_cast( + untyped_ros_message); + +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // Member: @(member.name) +@[ if isinstance(member.type, AbstractNestedType)]@ + { +@[ if isinstance(member.type, Array)]@ +@[ if not isinstance(member.type.value_type, (NamespacedType, AbstractWString))]@ + cdr << ros_message->@(member.name); +@[ else]@ +@[ if isinstance(member.type.value_type, AbstractWString)]@ + std::wstring wstr; +@[ end if]@ + for (size_t i = 0; i < @(member.type.size); i++) { +@[ if isinstance(member.type.value_type, NamespacedType)]@ + @('::'.join(member.type.value_type.namespaces))::typesupport_fastrtps_cpp::cdr_serialize( + ros_message->@(member.name)[i], + cdr); +@[ else]@ + rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message->@(member.name)[i], wstr); + cdr << wstr; +@[ end if]@ + } +@[ end if]@ +@[ else]@ +@[ if isinstance(member.type, BoundedSequence) or isinstance(member.type.value_type, (NamespacedType, AbstractWString))]@ + size_t size = ros_message->@(member.name).size(); +@[ if isinstance(member.type, BoundedSequence)]@ + if (size > @(member.type.maximum_size)) { + throw std::runtime_error("key array size exceeds upper bound"); + } +@[ end if]@ +@[ end if]@ +@[ if not isinstance(member.type.value_type, (NamespacedType, AbstractWString)) and not isinstance(member.type, BoundedSequence)]@ + cdr << ros_message->@(member.name); +@[ else]@ + cdr << static_cast(size); +@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename not in ('boolean', 'wchar')]@ + if (size > 0) { + cdr.serializeArray(&(ros_message->@(member.name)[0]), size); + } +@[ else]@ +@[ if isinstance(member.type.value_type, AbstractWString)]@ + std::wstring wstr; +@[ end if]@ + for (size_t i = 0; i < size; i++) { +@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'boolean']@ + cdr << (ros_message->@(member.name)[i] ? true : false); +@[ elif isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'wchar']@ + cdr << static_cast(ros_message->@(member.name)[i]); +@[ elif isinstance(member.type.value_type, AbstractWString)]@ + rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message->@(member.name)[i], wstr); + cdr << wstr; +@[ elif not isinstance(member.type.value_type, NamespacedType)]@ + cdr << ros_message->@(member.name)[i]; +@[ else]@ + @('::'.join(member.type.value_type.namespaces))::typesupport_fastrtps_cpp::cdr_serialize( + ros_message->@(member.name)[i], + cdr); +@[ end if]@ + } +@[ end if]@ +@[ end if]@ +@[ end if]@ + } +@[ elif isinstance(member.type, BasicType) and member.type.typename == 'boolean']@ + cdr << (ros_message->@(member.name) ? true : false); +@[ elif isinstance(member.type, BasicType) and member.type.typename == 'wchar']@ + cdr << static_cast(ros_message->@(member.name)); +@[ elif isinstance(member.type, AbstractWString)]@ + { + std::wstring wstr; + rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message->@(member.name), wstr); + cdr << wstr; + } +@[ elif not isinstance(member.type, NamespacedType)]@ + cdr << ros_message->@(member.name); +@[ else]@ + @('::'.join(member.type.namespaces))::typesupport_fastrtps_cpp::cdr_serialize( + ros_message->@(member.name), + cdr); +@[ end if]@ +@[end for]@ + return true; +@[ else]@ + static_cast(untyped_ros_message); + static_cast(cdr); + return false; +@[ end if]@ +} + +size_t +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +_@(message.structure.namespaced_type.name)__get_serialized_key_size( + const void * untyped_ros_message, + size_t initial_alignment) +{ +@[ if message.structure.has_any_member_with_annotation('key') ]@ + auto ros_message = + static_cast( + untyped_ros_message); + + size_t current_alignment = initial_alignment; + + const size_t padding = 4; + const size_t wchar_size = 4; + (void)padding; + (void)wchar_size; + +@[for member in message.structure.members]@ +@[ if not member.has_annotation('key')]@ +@[ continue]@ +@[ end if]@ + // Member: @(member.name) +@[ if isinstance(member.type, AbstractNestedType)]@ + { +@[ if isinstance(member.type, Array)]@ + size_t array_size = @(member.type.size); +@[ else]@ + size_t array_size = ros_message->@(member.name).size(); +@[ if isinstance(member.type, BoundedSequence)]@ + if (array_size > @(member.type.maximum_size)) { + throw std::runtime_error("array size exceeds upper bound"); + } +@[ end if]@ + + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding); +@[ end if]@ +@[ if isinstance(member.type.value_type, AbstractGenericString)]@ + for (size_t index = 0; index < array_size; ++index) { + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if isinstance(member.type.value_type, AbstractWString)]@ + wchar_size * +@[ end if]@ + (ros_message->@(member.name)[index].size() + 1); + } +@[ elif isinstance(member.type.value_type, BasicType)]@ + size_t item_size = sizeof(ros_message->@(member.name)[0]); + current_alignment += array_size * item_size + + eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); +@[ else] + for (size_t index = 0; index < array_size; ++index) { + current_alignment += + @('::'.join(member.type.value_type.namespaces))::typesupport_fastrtps_cpp::_@(message.structure.namespaced_type.name)__get_serialized_key_size( + ros_message->@(member.name)[index], current_alignment); + } +@[ end if]@ + } +@[ else]@ +@[ if isinstance(member.type, AbstractGenericString)]@ + current_alignment += padding + + eprosima::fastcdr::Cdr::alignment(current_alignment, padding) + +@[ if isinstance(member.type, AbstractWString)]@ + wchar_size * +@[ end if]@ + (ros_message->@(member.name).size() + 1); +@[ elif isinstance(member.type, BasicType)]@ + { + size_t item_size = sizeof(ros_message->@(member.name)); + current_alignment += item_size + + eprosima::fastcdr::Cdr::alignment(current_alignment, item_size); + } +@[ else] + current_alignment += + @('::'.join(member.type.namespaces))::typesupport_fastrtps_cpp::_@(message.structure.namespaced_type.name)__get_serialized_key_size( + ros_message->@(member.name), current_alignment); +@[ end if]@ +@[ end if]@ +@[end for]@ + + return current_alignment - initial_alignment; +@[ else]@ + static_cast(untyped_ros_message); + static_cast(initial_alignment); + return static_cast(0); +@[ end if]@ +} + +bool +ROSIDL_TYPESUPPORT_FASTRTPS_CPP_PUBLIC_@(package_name) +get_key_type_support_@(message.structure.namespaced_type.name)( + message_type_support_key_callbacks_t * key_callbacks) +{ + std::cout << "Initializing CPP interface @(message.structure.namespaced_type.name)" << std::endl; +@[ if message.structure.has_any_member_with_annotation('key') ]@ + key_callbacks->max_serialized_key_size = &_@(message.structure.namespaced_type.name)__max_serialized_key_size; + key_callbacks->cdr_deserialize_key = &_@(message.structure.namespaced_type.name)__cdr_deserialize_key; + key_callbacks->cdr_serialize_key = &_@(message.structure.namespaced_type.name)__cdr_serialize_key; + key_callbacks->get_serialized_key_size = &_@(message.structure.namespaced_type.name)__get_serialized_key_size; + return true; +@[ else]@ + static_cast(key_callbacks); + return false; +@[ end if]@ +} + static bool _@(message.structure.namespaced_type.name)__cdr_serialize( const void * untyped_ros_message, eprosima::fastcdr::Cdr & cdr) @@ -502,13 +814,21 @@ static size_t _@(message.structure.namespaced_type.name)__max_serialized_size(ch return ret_val; } +static bool _@(message.structure.namespaced_type.name)__get_key_type_support( message_type_support_key_callbacks_t * key_callbacks) +{ + bool ret_val; + ret_val = get_key_type_support_@(message.structure.namespaced_type.name)(key_callbacks); + return ret_val; +} + static message_type_support_callbacks_t _@(message.structure.namespaced_type.name)__callbacks = { "@('::'.join([package_name] + list(interface_path.parents[0].parts)))", "@(message.structure.namespaced_type.name)", _@(message.structure.namespaced_type.name)__cdr_serialize, _@(message.structure.namespaced_type.name)__cdr_deserialize, _@(message.structure.namespaced_type.name)__get_serialized_size, - _@(message.structure.namespaced_type.name)__max_serialized_size + _@(message.structure.namespaced_type.name)__max_serialized_size, + _@(message.structure.namespaced_type.name)__get_key_type_support }; static rosidl_message_type_support_t _@(message.structure.namespaced_type.name)__handle = {