15 #ifndef RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_
16 #define RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_
18 #include <fastcdr/FastBuffer.h>
19 #include <fastcdr/Cdr.h>
26 #include "rosidl_typesupport_fastrtps_c/wstring_conversion.hpp"
27 #include "rosidl_typesupport_fastrtps_cpp/wstring_conversion.hpp"
28 #include "rosidl_typesupport_introspection_cpp/field_types.hpp"
29 #include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
30 #include "rosidl_typesupport_introspection_cpp/service_introspection.hpp"
32 #include "rosidl_typesupport_introspection_c/message_introspection.h"
33 #include "rosidl_typesupport_introspection_c/service_introspection.h"
35 #include "rosidl_runtime_c/primitives_sequence_functions.h"
36 #include "rosidl_runtime_c/u16string_functions.h"
75 void * data =
nullptr;
77 data =
static_cast<void *
>(calloc(size, member_size));
82 sequence->
data = data;
83 sequence->
size = size;
100 sequence->
data =
nullptr;
105 assert(0 == sequence->
size);
110 template<
typename MembersType>
114 m_isGetKeyDefined =
false;
115 max_size_bound_ =
false;
119 align_(
size_t __align,
void * & __ptr) noexcept
121 const auto __intptr =
reinterpret_cast<uintptr_t
>(__ptr);
122 const auto __aligned = (__intptr - 1u + __align) & ~(__align - 1);
123 return __ptr =
reinterpret_cast<void *
>(__aligned);
126 template<
typename MembersType>
127 static size_t calculateMaxAlign(
const MembersType * members)
129 size_t max_align = 0;
131 for (uint32_t i = 0; i < members->member_count_; ++i) {
132 size_t alignment = 0;
133 const auto & member = members->members_[i];
135 if (member.is_array_ && (!member.array_size_ || member.is_upper_bound_)) {
138 switch (member.type_id_) {
139 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
140 alignment =
alignof(bool);
142 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
143 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
144 alignment =
alignof(uint8_t);
146 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
147 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
148 alignment =
alignof(char);
150 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
151 alignment =
alignof(float);
153 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
154 alignment =
alignof(double);
156 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
157 alignment =
alignof(int16_t);
159 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
160 alignment =
alignof(uint16_t);
162 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
163 alignment =
alignof(int32_t);
165 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
166 alignment =
alignof(uint32_t);
168 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
169 alignment =
alignof(int64_t);
171 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
172 alignment =
alignof(uint64_t);
174 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
178 rosidl_typesupport_introspection_c__MessageMembers>::value)
180 alignment =
alignof(rosidl_runtime_c__String);
185 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
187 rosidl_typesupport_introspection_c__MessageMembers>::value)
189 alignment =
alignof(rosidl_runtime_c__U16String);
194 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
196 auto sub_members = (
const MembersType *)member.members_->data;
197 alignment = calculateMaxAlign(sub_members);
203 if (alignment > max_align) {
204 max_align = alignment;
214 const rosidl_typesupport_introspection_cpp::MessageMember * member,
216 eprosima::fastcdr::Cdr & ser)
218 if (!member->is_array_) {
219 ser << *static_cast<T *>(field);
220 }
else if (member->array_size_ && !member->is_upper_bound_) {
221 ser.serializeArray(
static_cast<T *
>(field), member->array_size_);
230 void serialize_field<std::wstring>(
231 const rosidl_typesupport_introspection_cpp::MessageMember * member,
233 eprosima::fastcdr::Cdr & ser)
236 if (!member->is_array_) {
238 rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(*u16str, wstr);
242 if (member->array_size_ && !member->is_upper_bound_) {
243 size = member->array_size_;
245 size = member->size_function(field);
246 ser << static_cast<uint32_t>(size);
248 for (
size_t i = 0; i < size; ++i) {
249 const void * element = member->get_const_function(field, i);
251 rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(*u16str, wstr);
260 const rosidl_typesupport_introspection_c__MessageMember * member,
262 eprosima::fastcdr::Cdr & ser)
264 if (!member->is_array_) {
265 ser << *static_cast<T *>(field);
266 }
else if (member->array_size_ && !member->is_upper_bound_) {
267 ser.serializeArray(
static_cast<T *
>(field), member->array_size_);
270 ser.serializeSequence(
reinterpret_cast<T *
>(data.data), data.size);
276 void serialize_field<std::string>(
277 const rosidl_typesupport_introspection_c__MessageMember * member,
279 eprosima::fastcdr::Cdr & ser)
282 if (!member->is_array_) {
283 auto && str = CStringHelper::convert_to_std_string(field);
285 if (member->string_upper_bound_ && str.length() > member->string_upper_bound_ + 1) {
292 if (member->array_size_ && !member->is_upper_bound_) {
296 auto string_field =
static_cast<rosidl_runtime_c__String *
>(field);
297 for (
size_t i = 0; i < member->array_size_; ++i) {
298 tmpstring = string_field[i].
data;
299 ser.serialize(tmpstring);
302 auto & string_sequence_field =
303 *
reinterpret_cast<rosidl_runtime_c__String__Sequence *
>(field);
305 for (
size_t i = 0; i < string_sequence_field.size; ++i) {
307 CStringHelper::convert_to_std_string(string_sequence_field.data[i]));
309 ser << cpp_string_vector;
316 void serialize_field<std::wstring>(
317 const rosidl_typesupport_introspection_c__MessageMember * member,
319 eprosima::fastcdr::Cdr & ser)
322 if (!member->is_array_) {
323 auto u16str =
static_cast<rosidl_runtime_c__U16String *
>(field);
324 rosidl_typesupport_fastrtps_c::u16string_to_wstring(*u16str, wstr);
326 }
else if (member->array_size_ && !member->is_upper_bound_) {
327 auto array =
static_cast<rosidl_runtime_c__U16String *
>(field);
328 for (
size_t i = 0; i < member->array_size_; ++i) {
329 rosidl_typesupport_fastrtps_c::u16string_to_wstring(array[i], wstr);
333 auto sequence =
static_cast<rosidl_runtime_c__U16String__Sequence *
>(field);
334 ser << static_cast<uint32_t>(sequence->size);
335 for (
size_t i = 0; i < sequence->size; ++i) {
336 rosidl_typesupport_fastrtps_c::u16string_to_wstring(sequence->data[i], wstr);
343 const rosidl_typesupport_introspection_cpp::MessageMember * member,
345 void * & subros_message,
346 size_t sub_members_size,
350 void * ptr =
reinterpret_cast<void *
>(sub_members_size);
351 size_t vsize = vector->
size() /
reinterpret_cast<size_t>(align_(max_align, ptr));
352 if (member->is_upper_bound_ && vsize > member->array_size_) {
355 subros_message =
reinterpret_cast<void *
>(vector->data());
361 const rosidl_typesupport_introspection_c__MessageMember * member,
363 void * & subros_message,
367 if (member->is_upper_bound_ && tmpsequence->size > member->array_size_) {
370 subros_message =
reinterpret_cast<void *
>(tmpsequence->data);
371 return tmpsequence->size;
374 template<
typename MembersType>
376 eprosima::fastcdr::Cdr & ser,
377 const MembersType * members,
378 const void * ros_message)
const
383 for (uint32_t i = 0; i < members->member_count_; ++i) {
384 const auto member = members->members_ + i;
385 void * field =
const_cast<char *
>(
static_cast<const char *
>(ros_message)) + member->offset_;
386 switch (member->type_id_) {
387 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
388 if (!member->is_array_) {
391 ser << (*static_cast<uint8_t *>(field) ? true :
false);
393 serialize_field<bool>(member, field, ser);
396 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
397 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
398 serialize_field<uint8_t>(member, field, ser);
400 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
401 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
402 serialize_field<char>(member, field, ser);
404 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
405 serialize_field<float>(member, field, ser);
407 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
408 serialize_field<double>(member, field, ser);
410 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
411 serialize_field<int16_t>(member, field, ser);
413 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
414 serialize_field<uint16_t>(member, field, ser);
416 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
417 serialize_field<int32_t>(member, field, ser);
419 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
420 serialize_field<uint32_t>(member, field, ser);
422 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
423 serialize_field<int64_t>(member, field, ser);
425 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
426 serialize_field<uint64_t>(member, field, ser);
428 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
429 serialize_field<std::string>(member, field, ser);
431 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
432 serialize_field<std::wstring>(member, field, ser);
434 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
436 auto sub_members =
static_cast<const MembersType *
>(member->members_->data);
437 if (!member->is_array_) {
438 serializeROSmessage(ser, sub_members, field);
440 void * subros_message =
nullptr;
441 size_t array_size = 0;
442 size_t sub_members_size = sub_members->size_of_;
443 size_t max_align = calculateMaxAlign(sub_members);
445 if (member->array_size_ && !member->is_upper_bound_) {
446 subros_message = field;
447 array_size = member->array_size_;
450 member, field, subros_message, sub_members_size, max_align);
453 ser << (uint32_t)array_size;
456 for (
size_t index = 0; index < array_size; ++index) {
457 serializeROSmessage(ser, sub_members, subros_message);
458 subros_message =
static_cast<char *
>(subros_message) + sub_members_size;
459 subros_message = align_(max_align, subros_message);
475 const rosidl_typesupport_introspection_cpp::MessageMember * member,
477 size_t current_alignment)
479 const size_t padding = 4;
480 size_t item_size =
sizeof(T);
481 if (!member->is_array_) {
482 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
483 current_alignment += item_size;
484 }
else if (member->array_size_ && !member->is_upper_bound_) {
485 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
486 current_alignment += item_size * member->array_size_;
489 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
490 current_alignment += padding;
492 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
493 current_alignment += item_size * data.
size();
496 return current_alignment;
501 const rosidl_typesupport_introspection_cpp::MessageMember * member,
503 size_t current_alignment)
505 const size_t padding = 4;
506 size_t character_size =
507 (member->type_id_ == rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING) ? 4 : 1;
508 if (!member->is_array_) {
509 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
510 current_alignment += padding;
511 auto & str = *
static_cast<T *
>(field);
512 current_alignment += character_size * (str.size() + 1);
513 }
else if (member->array_size_ && !member->is_upper_bound_) {
514 auto str_arr =
static_cast<T *
>(field);
515 for (
size_t index = 0; index < member->array_size_; ++index) {
516 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
517 current_alignment += padding;
518 current_alignment += character_size * (str_arr[index].size() + 1);
522 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
523 current_alignment += padding;
524 for (
auto & it : data) {
525 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
526 current_alignment += padding;
527 current_alignment += character_size * (it.size() + 1);
530 return current_alignment;
536 const rosidl_typesupport_introspection_c__MessageMember * member,
538 size_t current_alignment)
540 const size_t padding = 4;
541 size_t item_size =
sizeof(T);
542 if (!member->is_array_) {
543 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
544 current_alignment += item_size;
545 }
else if (member->array_size_ && !member->is_upper_bound_) {
546 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
547 current_alignment += item_size * member->array_size_;
549 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
550 current_alignment += padding;
553 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
554 current_alignment += item_size * data.size;
556 return current_alignment;
561 const rosidl_typesupport_introspection_c__MessageMember * member,
563 size_t current_alignment);
567 size_t next_field_align_string<std::string>(
568 const rosidl_typesupport_introspection_c__MessageMember * member,
570 size_t current_alignment)
572 const size_t padding = 4;
574 if (!member->is_array_) {
577 if (member->array_size_ && !member->is_upper_bound_) {
578 auto string_field =
static_cast<rosidl_runtime_c__String *
>(field);
579 for (
size_t i = 0; i < member->array_size_; ++i) {
580 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
581 current_alignment += padding;
582 current_alignment += strlen(string_field[i].data) + 1;
585 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
586 current_alignment += padding;
587 auto & string_sequence_field =
588 *
reinterpret_cast<rosidl_runtime_c__String__Sequence *
>(field);
589 for (
size_t i = 0; i < string_sequence_field.size; ++i) {
591 &(string_sequence_field.data[i]), current_alignment);
595 return current_alignment;
600 size_t next_field_align_string<std::wstring>(
601 const rosidl_typesupport_introspection_c__MessageMember * member,
603 size_t current_alignment)
605 const size_t padding = 4;
606 if (!member->is_array_) {
607 auto u16str =
static_cast<rosidl_runtime_c__U16String *
>(field);
608 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
609 current_alignment += padding;
610 current_alignment += 4 * (u16str->size + 1);
612 if (member->array_size_ && !member->is_upper_bound_) {
613 auto string_field =
static_cast<rosidl_runtime_c__U16String *
>(field);
614 for (
size_t i = 0; i < member->array_size_; ++i) {
615 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
616 current_alignment += padding;
617 current_alignment += 4 * (string_field[i].size + 1);
620 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
621 current_alignment += padding;
622 auto & string_sequence_field =
623 *
reinterpret_cast<rosidl_runtime_c__U16String__Sequence *
>(field);
624 for (
size_t i = 0; i < string_sequence_field.size; ++i) {
625 current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
626 current_alignment += padding;
627 current_alignment += 4 * (string_sequence_field.data[i].size + 1);
631 return current_alignment;
634 template<
typename MembersType>
636 const MembersType * members,
637 const void * ros_message,
638 size_t current_alignment)
const
643 size_t initial_alignment = current_alignment;
645 for (uint32_t i = 0; i < members->member_count_; ++i) {
646 const auto member = members->members_ + i;
647 void * field =
const_cast<char *
>(
static_cast<const char *
>(ros_message)) + member->offset_;
648 switch (member->type_id_) {
649 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
650 current_alignment = next_field_align<bool>(member, field, current_alignment);
652 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
653 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
654 current_alignment = next_field_align<uint8_t>(member, field, current_alignment);
656 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
657 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
658 current_alignment = next_field_align<char>(member, field, current_alignment);
660 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
661 current_alignment = next_field_align<float>(member, field, current_alignment);
663 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
664 current_alignment = next_field_align<double>(member, field, current_alignment);
666 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
667 current_alignment = next_field_align<int16_t>(member, field, current_alignment);
669 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
670 current_alignment = next_field_align<uint16_t>(member, field, current_alignment);
672 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
673 current_alignment = next_field_align<int32_t>(member, field, current_alignment);
675 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
676 current_alignment = next_field_align<uint32_t>(member, field, current_alignment);
678 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
679 current_alignment = next_field_align<int64_t>(member, field, current_alignment);
681 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
682 current_alignment = next_field_align<uint64_t>(member, field, current_alignment);
684 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
685 current_alignment = next_field_align_string<std::string>(member, field, current_alignment);
687 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
688 current_alignment = next_field_align_string<std::wstring>(member, field, current_alignment);
690 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
692 auto sub_members =
static_cast<const MembersType *
>(member->members_->data);
693 if (!member->is_array_) {
694 current_alignment += getEstimatedSerializedSize(sub_members, field, current_alignment);
696 void * subros_message =
nullptr;
697 size_t array_size = 0;
698 size_t sub_members_size = sub_members->size_of_;
699 size_t max_align = calculateMaxAlign(sub_members);
701 if (member->array_size_ && !member->is_upper_bound_) {
702 subros_message = field;
703 array_size = member->array_size_;
706 member, field, subros_message, sub_members_size, max_align);
709 current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
712 for (
size_t index = 0; index < array_size; ++index) {
713 current_alignment += getEstimatedSerializedSize(
714 sub_members, subros_message, current_alignment);
715 subros_message =
static_cast<char *
>(subros_message) + sub_members_size;
716 subros_message = align_(max_align, subros_message);
726 return current_alignment - initial_alignment;
731 const rosidl_typesupport_introspection_cpp::MessageMember * member,
733 eprosima::fastcdr::Cdr & deser,
736 if (!member->is_array_) {
737 deser >> *
static_cast<T *
>(field);
738 }
else if (member->array_size_ && !member->is_upper_bound_) {
739 deser.deserializeArray(
static_cast<T *
>(field), member->array_size_);
750 inline void deserialize_field<std::string>(
751 const rosidl_typesupport_introspection_cpp::MessageMember * member,
753 eprosima::fastcdr::Cdr & deser,
756 if (!member->is_array_) {
764 }
else if (member->array_size_ && !member->is_upper_bound_) {
767 for (
size_t i = 0; i < member->array_size_; ++i) {
771 deser.deserializeArray(array, member->array_size_);
782 inline void deserialize_field<std::wstring>(
783 const rosidl_typesupport_introspection_cpp::MessageMember * member,
785 eprosima::fastcdr::Cdr & deser,
790 if (!member->is_array_) {
792 rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(
796 if (member->array_size_ && !member->is_upper_bound_) {
797 size =
static_cast<uint32_t
>(member->array_size_);
800 member->resize_function(field, size);
802 for (
size_t i = 0; i < size; ++i) {
803 void * element = member->get_function(field, i);
806 rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(wstr, *u16str);
813 const rosidl_typesupport_introspection_c__MessageMember * member,
815 eprosima::fastcdr::Cdr & deser,
819 if (!member->is_array_) {
820 deser >> *
static_cast<T *
>(field);
821 }
else if (member->array_size_ && !member->is_upper_bound_) {
822 deser.deserializeArray(
static_cast<T *
>(field), member->array_size_);
828 deser.deserializeArray(
reinterpret_cast<T *
>(data.data), dsize);
833 inline void deserialize_field<std::string>(
834 const rosidl_typesupport_introspection_c__MessageMember * member,
836 eprosima::fastcdr::Cdr & deser,
840 if (!member->is_array_) {
842 CStringHelper::assign(deser, field, call_new);
844 if (member->array_size_ && !member->is_upper_bound_) {
845 auto deser_field =
static_cast<rosidl_runtime_c__String *
>(field);
849 for (
size_t i = 0; i < member->array_size_; ++i) {
850 deser.deserialize(tmpstring);
851 if (!rosidl_runtime_c__String__assign(&deser_field[i], tmpstring.
c_str())) {
857 deser >> cpp_string_vector;
859 auto & string_sequence_field =
860 *
reinterpret_cast<rosidl_runtime_c__String__Sequence *
>(field);
862 !rosidl_runtime_c__String__Sequence__init(
863 &string_sequence_field, cpp_string_vector.size()))
868 for (
size_t i = 0; i < cpp_string_vector.size(); ++i) {
870 !rosidl_runtime_c__String__assign(
871 &string_sequence_field.data[i], cpp_string_vector[i].c_str()))
881 inline void deserialize_field<std::wstring>(
882 const rosidl_typesupport_introspection_c__MessageMember * member,
884 eprosima::fastcdr::Cdr & deser,
889 if (!member->is_array_) {
891 rosidl_typesupport_fastrtps_c::wstring_to_u16string(
892 wstr, *
static_cast<rosidl_runtime_c__U16String *
>(field));
893 }
else if (member->array_size_ && !member->is_upper_bound_) {
894 auto array =
static_cast<rosidl_runtime_c__U16String *
>(field);
895 for (
size_t i = 0; i < member->array_size_; ++i) {
897 rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, array[i]);
902 auto sequence =
static_cast<rosidl_runtime_c__U16String__Sequence *
>(field);
903 if (!rosidl_runtime_c__U16String__Sequence__init(sequence, size)) {
904 throw std::runtime_error(
"unable to initialize rosidl_runtime_c__U16String sequence");
906 for (
size_t i = 0; i < sequence->size; ++i) {
908 rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, sequence->data[i]);
914 const rosidl_typesupport_introspection_cpp::MessageMember * member,
915 eprosima::fastcdr::Cdr & deser,
917 void * & subros_message,
919 size_t sub_members_size,
930 void * ptr =
reinterpret_cast<void *
>(sub_members_size);
931 vector->
resize(vsize * (
size_t)align_(max_align, ptr));
932 subros_message =
reinterpret_cast<void *
>(vector->data());
937 const rosidl_typesupport_introspection_c__MessageMember * member,
938 eprosima::fastcdr::Cdr & deser,
940 void * & subros_message,
942 size_t sub_members_size,
951 subros_message =
reinterpret_cast<void *
>(tmpsequence->data);
955 template<
typename MembersType>
957 eprosima::fastcdr::Cdr & deser,
958 const MembersType * members,
965 for (uint32_t i = 0; i < members->member_count_; ++i) {
966 const auto * member = members->members_ + i;
967 void * field =
static_cast<char *
>(ros_message) + member->offset_;
968 switch (member->type_id_) {
969 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
970 deserialize_field<bool>(member, field, deser, call_new);
972 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
973 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
974 deserialize_field<uint8_t>(member, field, deser, call_new);
976 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
977 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
978 deserialize_field<char>(member, field, deser, call_new);
980 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
981 deserialize_field<float>(member, field, deser, call_new);
983 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
984 deserialize_field<double>(member, field, deser, call_new);
986 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
987 deserialize_field<int16_t>(member, field, deser, call_new);
989 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
990 deserialize_field<uint16_t>(member, field, deser, call_new);
992 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
993 deserialize_field<int32_t>(member, field, deser, call_new);
995 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
996 deserialize_field<uint32_t>(member, field, deser, call_new);
998 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
999 deserialize_field<int64_t>(member, field, deser, call_new);
1001 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
1002 deserialize_field<uint64_t>(member, field, deser, call_new);
1004 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
1005 deserialize_field<std::string>(member, field, deser, call_new);
1007 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
1008 deserialize_field<std::wstring>(member, field, deser, call_new);
1010 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
1012 auto sub_members = (
const MembersType *)member->members_->data;
1013 if (!member->is_array_) {
1014 deserializeROSmessage(deser, sub_members, field, call_new);
1016 void * subros_message =
nullptr;
1017 size_t array_size = 0;
1018 size_t sub_members_size = sub_members->size_of_;
1019 size_t max_align = calculateMaxAlign(sub_members);
1020 bool recall_new = call_new;
1022 if (member->array_size_ && !member->is_upper_bound_) {
1023 subros_message = field;
1024 array_size = member->array_size_;
1027 member, deser, field, subros_message,
1028 call_new, sub_members_size, max_align);
1032 for (
size_t index = 0; index < array_size; ++index) {
1033 deserializeROSmessage(deser, sub_members, subros_message, recall_new);
1034 subros_message =
static_cast<char *
>(subros_message) + sub_members_size;
1035 subros_message = align_(max_align, subros_message);
1048 template<
typename MembersType>
1050 const MembersType * members,
size_t current_alignment)
1054 size_t initial_alignment = current_alignment;
1056 const size_t padding = 4;
1058 for (uint32_t i = 0; i < members->member_count_; ++i) {
1059 const auto * member = members->members_ + i;
1061 size_t array_size = 1;
1062 if (member->is_array_) {
1063 array_size = member->array_size_;
1065 if (0 == array_size || member->is_upper_bound_) {
1066 this->max_size_bound_ =
false;
1067 current_alignment += padding +
1068 eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
1072 switch (member->type_id_) {
1073 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
1074 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
1075 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
1076 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
1077 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
1078 current_alignment += array_size *
sizeof(int8_t);
1080 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
1081 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
1082 current_alignment += array_size *
sizeof(uint16_t) +
1083 eprosima::fastcdr::Cdr::alignment(current_alignment,
sizeof(uint16_t));
1085 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
1086 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
1087 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
1088 current_alignment += array_size *
sizeof(uint32_t) +
1089 eprosima::fastcdr::Cdr::alignment(current_alignment,
sizeof(uint32_t));
1091 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
1092 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
1093 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
1094 current_alignment += array_size *
sizeof(uint64_t) +
1095 eprosima::fastcdr::Cdr::alignment(current_alignment,
sizeof(uint64_t));
1097 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
1098 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
1100 this->max_size_bound_ =
false;
1101 size_t character_size =
1102 (member->type_id_ == rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING) ? 4 : 1;
1103 for (
size_t index = 0; index < array_size; ++index) {
1104 current_alignment += padding +
1105 eprosima::fastcdr::Cdr::alignment(current_alignment, padding) +
1106 character_size * (member->string_upper_bound_ + 1);
1110 case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
1112 auto sub_members =
static_cast<const MembersType *
>(member->members_->data);
1113 for (
size_t index = 0; index < array_size; ++index) {
1114 current_alignment += calculateMaxSerializedSize(sub_members, current_alignment);
1123 return current_alignment - initial_alignment;
1126 template<
typename MembersType>
1128 const void * ros_message,
const void * impl)
const
1130 if (max_size_bound_) {
1134 assert(ros_message);
1141 if (members_->member_count_ != 0) {
1142 ret_val += TypeSupport::getEstimatedSerializedSize(members_, ros_message, 0);
1150 template<
typename MembersType>
1152 const void * ros_message, eprosima::fastcdr::Cdr & ser,
const void * impl)
const
1154 assert(ros_message);
1158 ser.serialize_encapsulation();
1161 if (members_->member_count_ != 0) {
1162 TypeSupport::serializeROSmessage(ser, members_, ros_message);
1170 template<
typename MembersType>
1172 eprosima::fastcdr::Cdr & deser,
void * ros_message,
const void * impl)
const
1174 assert(ros_message);
1178 deser.read_encapsulation();
1181 if (members_->member_count_ != 0) {
1182 TypeSupport::deserializeROSmessage(deser, members_, ros_message,
false);
1194 #endif // RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_