rmw_fastrtps_dynamic_cpp  master
Implement the ROS middleware interface using eProsima FastRTPS dynamic code generation in C++.
All Classes Namespaces Files Functions Variables Typedefs Macros
TypeSupport_impl.hpp
Go to the documentation of this file.
1 // Copyright 2016-2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_
16 #define RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_
17 
18 #include <fastcdr/FastBuffer.h>
19 #include <fastcdr/Cdr.h>
20 #include <cassert>
21 #include <string>
22 #include <vector>
23 
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"
31 
32 #include "rosidl_typesupport_introspection_c/message_introspection.h"
33 #include "rosidl_typesupport_introspection_c/service_introspection.h"
34 
35 #include "rosidl_runtime_c/primitives_sequence_functions.h"
36 #include "rosidl_runtime_c/u16string_functions.h"
37 
39 {
40 
41 template<typename T>
43 
44 // multiple definitions of ambiguous primitive types
46 SPECIALIZE_GENERIC_C_SEQUENCE(byte, uint8_t)
48 SPECIALIZE_GENERIC_C_SEQUENCE(float32, float)
49 SPECIALIZE_GENERIC_C_SEQUENCE(float64, double)
51 SPECIALIZE_GENERIC_C_SEQUENCE(int16, int16_t)
52 SPECIALIZE_GENERIC_C_SEQUENCE(uint16, uint16_t)
53 SPECIALIZE_GENERIC_C_SEQUENCE(int32, int32_t)
54 SPECIALIZE_GENERIC_C_SEQUENCE(uint32, uint32_t)
55 SPECIALIZE_GENERIC_C_SEQUENCE(int64, int64_t)
56 SPECIALIZE_GENERIC_C_SEQUENCE(uint64, uint64_t)
57 
59 {
60  void * data;
62  size_t size;
64  size_t capacity;
66 
67 inline
68 bool
70  rosidl_runtime_c__void__Sequence * sequence, size_t size, size_t member_size)
71 {
72  if (!sequence) {
73  return false;
74  }
75  void * data = nullptr;
76  if (size) {
77  data = static_cast<void *>(calloc(size, member_size));
78  if (!data) {
79  return false;
80  }
81  }
82  sequence->data = data;
83  sequence->size = size;
84  sequence->capacity = size;
85  return true;
86 }
87 
88 inline
89 void
91 {
92  if (!sequence) {
93  return;
94  }
95  if (sequence->data) {
96  // ensure that data and capacity values are consistent
97  assert(sequence->capacity > 0);
98  // finalize all sequence elements
99  free(sequence->data);
100  sequence->data = nullptr;
101  sequence->size = 0;
102  sequence->capacity = 0;
103  } else {
104  // ensure that data, size, and capacity values are consistent
105  assert(0 == sequence->size);
106  assert(0 == sequence->capacity);
107  }
108 }
109 
110 template<typename MembersType>
111 TypeSupport<MembersType>::TypeSupport(const void * ros_type_support)
112 : BaseTypeSupport(ros_type_support)
113 {
114  m_isGetKeyDefined = false;
115  max_size_bound_ = false;
116 }
117 
118 static inline void *
119 align_(size_t __align, void * & __ptr) noexcept
120 {
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);
124 }
125 
126 template<typename MembersType>
127 static size_t calculateMaxAlign(const MembersType * members)
128 {
129  size_t max_align = 0;
130 
131  for (uint32_t i = 0; i < members->member_count_; ++i) {
132  size_t alignment = 0;
133  const auto & member = members->members_[i];
134 
135  if (member.is_array_ && (!member.array_size_ || member.is_upper_bound_)) {
136  alignment = alignof(std::vector<unsigned char>);
137  } else {
138  switch (member.type_id_) {
139  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BOOL:
140  alignment = alignof(bool);
141  break;
142  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE:
143  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8:
144  alignment = alignof(uint8_t);
145  break;
146  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR:
147  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8:
148  alignment = alignof(char);
149  break;
150  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
151  alignment = alignof(float);
152  break;
153  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
154  alignment = alignof(double);
155  break;
156  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
157  alignment = alignof(int16_t);
158  break;
159  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
160  alignment = alignof(uint16_t);
161  break;
162  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
163  alignment = alignof(int32_t);
164  break;
165  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
166  alignment = alignof(uint32_t);
167  break;
168  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
169  alignment = alignof(int64_t);
170  break;
171  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
172  alignment = alignof(uint64_t);
173  break;
174  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
175  // Note: specialization needed because calculateMaxAlign is called before
176  // casting submembers as std::string, returned value is the same on i386
177  if (std::is_same<MembersType,
178  rosidl_typesupport_introspection_c__MessageMembers>::value)
179  {
180  alignment = alignof(rosidl_runtime_c__String);
181  } else {
182  alignment = alignof(std::string);
183  }
184  break;
185  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
186  if (std::is_same<MembersType,
187  rosidl_typesupport_introspection_c__MessageMembers>::value)
188  {
189  alignment = alignof(rosidl_runtime_c__U16String);
190  } else {
191  alignment = alignof(std::u16string);
192  }
193  break;
194  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
195  {
196  auto sub_members = (const MembersType *)member.members_->data;
197  alignment = calculateMaxAlign(sub_members);
198  }
199  break;
200  }
201  }
202 
203  if (alignment > max_align) {
204  max_align = alignment;
205  }
206  }
207 
208  return max_align;
209 }
210 
211 // C++ specialization
212 template<typename T>
214  const rosidl_typesupport_introspection_cpp::MessageMember * member,
215  void * field,
216  eprosima::fastcdr::Cdr & ser)
217 {
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_);
222  } else {
223  std::vector<T> & data = *reinterpret_cast<std::vector<T> *>(field);
224  ser << data;
225  }
226 }
227 
228 template<>
229 inline
230 void serialize_field<std::wstring>(
231  const rosidl_typesupport_introspection_cpp::MessageMember * member,
232  void * field,
233  eprosima::fastcdr::Cdr & ser)
234 {
235  std::wstring wstr;
236  if (!member->is_array_) {
237  auto u16str = static_cast<std::u16string *>(field);
238  rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(*u16str, wstr);
239  ser << wstr;
240  } else {
241  size_t size;
242  if (member->array_size_ && !member->is_upper_bound_) {
243  size = member->array_size_;
244  } else {
245  size = member->size_function(field);
246  ser << static_cast<uint32_t>(size);
247  }
248  for (size_t i = 0; i < size; ++i) {
249  const void * element = member->get_const_function(field, i);
250  auto u16str = static_cast<const std::u16string *>(element);
251  rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(*u16str, wstr);
252  ser << wstr;
253  }
254  }
255 }
256 
257 // C specialization
258 template<typename T>
260  const rosidl_typesupport_introspection_c__MessageMember * member,
261  void * field,
262  eprosima::fastcdr::Cdr & ser)
263 {
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_);
268  } else {
269  auto & data = *reinterpret_cast<typename GenericCSequence<T>::type *>(field);
270  ser.serializeSequence(reinterpret_cast<T *>(data.data), data.size);
271  }
272 }
273 
274 template<>
275 inline
276 void serialize_field<std::string>(
277  const rosidl_typesupport_introspection_c__MessageMember * member,
278  void * field,
279  eprosima::fastcdr::Cdr & ser)
280 {
282  if (!member->is_array_) {
283  auto && str = CStringHelper::convert_to_std_string(field);
284  // Control maximum length.
285  if (member->string_upper_bound_ && str.length() > member->string_upper_bound_ + 1) {
286  throw std::runtime_error("string overcomes the maximum length");
287  }
288  ser << str;
289  } else {
290  // First, cast field to rosidl_generator_c
291  // Then convert to a std::string using StringHelper and serialize the std::string
292  if (member->array_size_ && !member->is_upper_bound_) {
293  // tmpstring is defined here and not below to avoid
294  // memory allocation in every iteration of the for loop
295  std::string tmpstring;
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);
300  }
301  } else {
302  auto & string_sequence_field =
303  *reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
304  std::vector<std::string> cpp_string_vector;
305  for (size_t i = 0; i < string_sequence_field.size; ++i) {
306  cpp_string_vector.push_back(
307  CStringHelper::convert_to_std_string(string_sequence_field.data[i]));
308  }
309  ser << cpp_string_vector;
310  }
311  }
312 }
313 
314 template<>
315 inline
316 void serialize_field<std::wstring>(
317  const rosidl_typesupport_introspection_c__MessageMember * member,
318  void * field,
319  eprosima::fastcdr::Cdr & ser)
320 {
321  std::wstring wstr;
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);
325  ser << 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);
330  ser << wstr;
331  }
332  } else {
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);
337  ser << wstr;
338  }
339  }
340 }
341 inline
343  const rosidl_typesupport_introspection_cpp::MessageMember * member,
344  void * field,
345  void * & subros_message,
346  size_t sub_members_size,
347  size_t max_align)
348 {
349  auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
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_) {
353  throw std::runtime_error("vector overcomes the maximum length");
354  }
355  subros_message = reinterpret_cast<void *>(vector->data());
356  return vsize;
357 }
358 
359 inline
361  const rosidl_typesupport_introspection_c__MessageMember * member,
362  void * field,
363  void * & subros_message,
364  size_t, size_t)
365 {
366  auto tmpsequence = static_cast<rosidl_runtime_c__void__Sequence *>(field);
367  if (member->is_upper_bound_ && tmpsequence->size > member->array_size_) {
368  throw std::runtime_error("vector overcomes the maximum length");
369  }
370  subros_message = reinterpret_cast<void *>(tmpsequence->data);
371  return tmpsequence->size;
372 }
373 
374 template<typename MembersType>
376  eprosima::fastcdr::Cdr & ser,
377  const MembersType * members,
378  const void * ros_message) const
379 {
380  assert(members);
381  assert(ros_message);
382 
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_) {
389  // don't cast to bool here because if the bool is
390  // uninitialized the random value can't be deserialized
391  ser << (*static_cast<uint8_t *>(field) ? true : false);
392  } else {
393  serialize_field<bool>(member, field, ser);
394  }
395  break;
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);
399  break;
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);
403  break;
404  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
405  serialize_field<float>(member, field, ser);
406  break;
407  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
408  serialize_field<double>(member, field, ser);
409  break;
410  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
411  serialize_field<int16_t>(member, field, ser);
412  break;
413  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
414  serialize_field<uint16_t>(member, field, ser);
415  break;
416  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
417  serialize_field<int32_t>(member, field, ser);
418  break;
419  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
420  serialize_field<uint32_t>(member, field, ser);
421  break;
422  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
423  serialize_field<int64_t>(member, field, ser);
424  break;
425  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
426  serialize_field<uint64_t>(member, field, ser);
427  break;
428  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
429  serialize_field<std::string>(member, field, ser);
430  break;
431  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
432  serialize_field<std::wstring>(member, field, ser);
433  break;
434  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
435  {
436  auto sub_members = static_cast<const MembersType *>(member->members_->data);
437  if (!member->is_array_) {
438  serializeROSmessage(ser, sub_members, field);
439  } else {
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);
444 
445  if (member->array_size_ && !member->is_upper_bound_) {
446  subros_message = field;
447  array_size = member->array_size_;
448  } else {
449  array_size = get_array_size_and_assign_field(
450  member, field, subros_message, sub_members_size, max_align);
451 
452  // Serialize length
453  ser << (uint32_t)array_size;
454  }
455 
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);
460  }
461  }
462  }
463  break;
464  default:
465  throw std::runtime_error("unknown type");
466  }
467  }
468 
469  return true;
470 }
471 
472 // C++ specialization
473 template<typename T>
475  const rosidl_typesupport_introspection_cpp::MessageMember * member,
476  void * field,
477  size_t current_alignment)
478 {
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_;
487  } else {
488  std::vector<T> & data = *reinterpret_cast<std::vector<T> *>(field);
489  current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
490  current_alignment += padding;
491  if (!data.empty()) {
492  current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
493  current_alignment += item_size * data.size();
494  }
495  }
496  return current_alignment;
497 }
498 
499 template<typename T>
501  const rosidl_typesupport_introspection_cpp::MessageMember * member,
502  void * field,
503  size_t current_alignment)
504 {
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);
519  }
520  } else {
521  auto & data = *reinterpret_cast<std::vector<T> *>(field);
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);
528  }
529  }
530  return current_alignment;
531 }
532 
533 // C specialization
534 template<typename T>
536  const rosidl_typesupport_introspection_c__MessageMember * member,
537  void * field,
538  size_t current_alignment)
539 {
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_;
548  } else {
549  current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, padding);
550  current_alignment += padding;
551 
552  auto & data = *reinterpret_cast<typename GenericCSequence<T>::type *>(field);
553  current_alignment += eprosima::fastcdr::Cdr::alignment(current_alignment, item_size);
554  current_alignment += item_size * data.size;
555  }
556  return current_alignment;
557 }
558 
559 template<typename T>
561  const rosidl_typesupport_introspection_c__MessageMember * member,
562  void * field,
563  size_t current_alignment);
564 
565 template<>
566 inline
567 size_t next_field_align_string<std::string>(
568  const rosidl_typesupport_introspection_c__MessageMember * member,
569  void * field,
570  size_t current_alignment)
571 {
572  const size_t padding = 4;
574  if (!member->is_array_) {
575  current_alignment = CStringHelper::next_field_align(field, current_alignment);
576  } else {
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;
583  }
584  } else {
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) {
590  current_alignment = CStringHelper::next_field_align(
591  &(string_sequence_field.data[i]), current_alignment);
592  }
593  }
594  }
595  return current_alignment;
596 }
597 
598 template<>
599 inline
600 size_t next_field_align_string<std::wstring>(
601  const rosidl_typesupport_introspection_c__MessageMember * member,
602  void * field,
603  size_t current_alignment)
604 {
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);
611  } else {
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);
618  }
619  } else {
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);
628  }
629  }
630  }
631  return current_alignment;
632 }
633 
634 template<typename MembersType>
636  const MembersType * members,
637  const void * ros_message,
638  size_t current_alignment) const
639 {
640  assert(members);
641  assert(ros_message);
642 
643  size_t initial_alignment = current_alignment;
644 
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);
651  break;
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);
655  break;
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);
659  break;
660  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
661  current_alignment = next_field_align<float>(member, field, current_alignment);
662  break;
663  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
664  current_alignment = next_field_align<double>(member, field, current_alignment);
665  break;
666  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
667  current_alignment = next_field_align<int16_t>(member, field, current_alignment);
668  break;
669  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
670  current_alignment = next_field_align<uint16_t>(member, field, current_alignment);
671  break;
672  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
673  current_alignment = next_field_align<int32_t>(member, field, current_alignment);
674  break;
675  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
676  current_alignment = next_field_align<uint32_t>(member, field, current_alignment);
677  break;
678  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
679  current_alignment = next_field_align<int64_t>(member, field, current_alignment);
680  break;
681  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
682  current_alignment = next_field_align<uint64_t>(member, field, current_alignment);
683  break;
684  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
685  current_alignment = next_field_align_string<std::string>(member, field, current_alignment);
686  break;
687  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
688  current_alignment = next_field_align_string<std::wstring>(member, field, current_alignment);
689  break;
690  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
691  {
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);
695  } else {
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);
700 
701  if (member->array_size_ && !member->is_upper_bound_) {
702  subros_message = field;
703  array_size = member->array_size_;
704  } else {
705  array_size = get_array_size_and_assign_field(
706  member, field, subros_message, sub_members_size, max_align);
707 
708  // Length serialization
709  current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
710  }
711 
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);
717  }
718  }
719  }
720  break;
721  default:
722  throw std::runtime_error("unknown type");
723  }
724  }
725 
726  return current_alignment - initial_alignment;
727 }
728 
729 template<typename T>
731  const rosidl_typesupport_introspection_cpp::MessageMember * member,
732  void * field,
733  eprosima::fastcdr::Cdr & deser,
734  bool call_new)
735 {
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_);
740  } else {
741  auto & vector = *reinterpret_cast<std::vector<T> *>(field);
742  if (call_new) {
743  new(&vector) std::vector<T>;
744  }
745  deser >> vector;
746  }
747 }
748 
749 template<>
750 inline void deserialize_field<std::string>(
751  const rosidl_typesupport_introspection_cpp::MessageMember * member,
752  void * field,
753  eprosima::fastcdr::Cdr & deser,
754  bool call_new)
755 {
756  if (!member->is_array_) {
757  if (call_new) {
758  // Because std::string is a complex datatype, we need to make sure that
759  // the memory is initialized to something reasonable before eventually
760  // passing it as a reference to Fast-CDR.
761  new(field) std::string();
762  }
763  deser >> *static_cast<std::string *>(field);
764  } else if (member->array_size_ && !member->is_upper_bound_) {
765  std::string * array = static_cast<std::string *>(field);
766  if (call_new) {
767  for (size_t i = 0; i < member->array_size_; ++i) {
768  new(&array[i]) std::string();
769  }
770  }
771  deser.deserializeArray(array, member->array_size_);
772  } else {
773  auto & vector = *reinterpret_cast<std::vector<std::string> *>(field);
774  if (call_new) {
775  new(&vector) std::vector<std::string>;
776  }
777  deser >> vector;
778  }
779 }
780 
781 template<>
782 inline void deserialize_field<std::wstring>(
783  const rosidl_typesupport_introspection_cpp::MessageMember * member,
784  void * field,
785  eprosima::fastcdr::Cdr & deser,
786  bool call_new)
787 {
788  (void)call_new;
789  std::wstring wstr;
790  if (!member->is_array_) {
791  deser >> wstr;
792  rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(
793  wstr, *static_cast<std::u16string *>(field));
794  } else {
795  uint32_t size;
796  if (member->array_size_ && !member->is_upper_bound_) {
797  size = static_cast<uint32_t>(member->array_size_);
798  } else {
799  deser >> size;
800  member->resize_function(field, size);
801  }
802  for (size_t i = 0; i < size; ++i) {
803  void * element = member->get_function(field, i);
804  auto u16str = static_cast<std::u16string *>(element);
805  deser >> wstr;
806  rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(wstr, *u16str);
807  }
808  }
809 }
810 
811 template<typename T>
813  const rosidl_typesupport_introspection_c__MessageMember * member,
814  void * field,
815  eprosima::fastcdr::Cdr & deser,
816  bool call_new)
817 {
818  (void)call_new;
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_);
823  } else {
824  auto & data = *reinterpret_cast<typename GenericCSequence<T>::type *>(field);
825  int32_t dsize = 0;
826  deser >> dsize;
827  GenericCSequence<T>::init(&data, dsize);
828  deser.deserializeArray(reinterpret_cast<T *>(data.data), dsize);
829  }
830 }
831 
832 template<>
833 inline void deserialize_field<std::string>(
834  const rosidl_typesupport_introspection_c__MessageMember * member,
835  void * field,
836  eprosima::fastcdr::Cdr & deser,
837  bool call_new)
838 {
839  (void)call_new;
840  if (!member->is_array_) {
842  CStringHelper::assign(deser, field, call_new);
843  } else {
844  if (member->array_size_ && !member->is_upper_bound_) {
845  auto deser_field = static_cast<rosidl_runtime_c__String *>(field);
846  // tmpstring is defined here and not below to avoid
847  // memory allocation in every iteration of the for loop
848  std::string tmpstring;
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())) {
852  throw std::runtime_error("unable to assign rosidl_runtime_c__String");
853  }
854  }
855  } else {
856  std::vector<std::string> cpp_string_vector;
857  deser >> cpp_string_vector;
858 
859  auto & string_sequence_field =
860  *reinterpret_cast<rosidl_runtime_c__String__Sequence *>(field);
861  if (
862  !rosidl_runtime_c__String__Sequence__init(
863  &string_sequence_field, cpp_string_vector.size()))
864  {
865  throw std::runtime_error("unable to initialize rosidl_runtime_c__String array");
866  }
867 
868  for (size_t i = 0; i < cpp_string_vector.size(); ++i) {
869  if (
870  !rosidl_runtime_c__String__assign(
871  &string_sequence_field.data[i], cpp_string_vector[i].c_str()))
872  {
873  throw std::runtime_error("unable to assign rosidl_runtime_c__String");
874  }
875  }
876  }
877  }
878 }
879 
880 template<>
881 inline void deserialize_field<std::wstring>(
882  const rosidl_typesupport_introspection_c__MessageMember * member,
883  void * field,
884  eprosima::fastcdr::Cdr & deser,
885  bool call_new)
886 {
887  (void)call_new;
888  std::wstring wstr;
889  if (!member->is_array_) {
890  deser >> wstr;
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) {
896  deser >> wstr;
897  rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, array[i]);
898  }
899  } else {
900  uint32_t size;
901  deser >> size;
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");
905  }
906  for (size_t i = 0; i < sequence->size; ++i) {
907  deser >> wstr;
908  rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, sequence->data[i]);
909  }
910  }
911 }
912 
914  const rosidl_typesupport_introspection_cpp::MessageMember * member,
915  eprosima::fastcdr::Cdr & deser,
916  void * field,
917  void * & subros_message,
918  bool call_new,
919  size_t sub_members_size,
920  size_t max_align)
921 {
922  (void)member;
923  uint32_t vsize = 0;
924  // Deserialize length
925  deser >> vsize;
926  auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
927  if (call_new) {
928  new(vector) std::vector<unsigned char>;
929  }
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());
933  return vsize;
934 }
935 
937  const rosidl_typesupport_introspection_c__MessageMember * member,
938  eprosima::fastcdr::Cdr & deser,
939  void * field,
940  void * & subros_message,
941  bool,
942  size_t sub_members_size,
943  size_t)
944 {
945  (void)member;
946  // Deserialize length
947  uint32_t vsize = 0;
948  deser >> vsize;
949  auto tmpsequence = static_cast<rosidl_runtime_c__void__Sequence *>(field);
950  rosidl_runtime_c__void__Sequence__init(tmpsequence, vsize, sub_members_size);
951  subros_message = reinterpret_cast<void *>(tmpsequence->data);
952  return vsize;
953 }
954 
955 template<typename MembersType>
957  eprosima::fastcdr::Cdr & deser,
958  const MembersType * members,
959  void * ros_message,
960  bool call_new) const
961 {
962  assert(members);
963  assert(ros_message);
964 
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);
971  break;
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);
975  break;
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);
979  break;
980  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT32:
981  deserialize_field<float>(member, field, deser, call_new);
982  break;
983  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_FLOAT64:
984  deserialize_field<double>(member, field, deser, call_new);
985  break;
986  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16:
987  deserialize_field<int16_t>(member, field, deser, call_new);
988  break;
989  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16:
990  deserialize_field<uint16_t>(member, field, deser, call_new);
991  break;
992  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32:
993  deserialize_field<int32_t>(member, field, deser, call_new);
994  break;
995  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32:
996  deserialize_field<uint32_t>(member, field, deser, call_new);
997  break;
998  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64:
999  deserialize_field<int64_t>(member, field, deser, call_new);
1000  break;
1001  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64:
1002  deserialize_field<uint64_t>(member, field, deser, call_new);
1003  break;
1004  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
1005  deserialize_field<std::string>(member, field, deser, call_new);
1006  break;
1007  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
1008  deserialize_field<std::wstring>(member, field, deser, call_new);
1009  break;
1010  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
1011  {
1012  auto sub_members = (const MembersType *)member->members_->data;
1013  if (!member->is_array_) {
1014  deserializeROSmessage(deser, sub_members, field, call_new);
1015  } else {
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;
1021 
1022  if (member->array_size_ && !member->is_upper_bound_) {
1023  subros_message = field;
1024  array_size = member->array_size_;
1025  } else {
1026  array_size = get_submessage_array_deserialize(
1027  member, deser, field, subros_message,
1028  call_new, sub_members_size, max_align);
1029  recall_new = true;
1030  }
1031 
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);
1036  }
1037  }
1038  }
1039  break;
1040  default:
1041  throw std::runtime_error("unknown type");
1042  }
1043  }
1044 
1045  return true;
1046 }
1047 
1048 template<typename MembersType>
1050  const MembersType * members, size_t current_alignment)
1051 {
1052  assert(members);
1053 
1054  size_t initial_alignment = current_alignment;
1055 
1056  const size_t padding = 4;
1057 
1058  for (uint32_t i = 0; i < members->member_count_; ++i) {
1059  const auto * member = members->members_ + i;
1060 
1061  size_t array_size = 1;
1062  if (member->is_array_) {
1063  array_size = member->array_size_;
1064  // Whether it is a sequence.
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);
1069  }
1070  }
1071 
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);
1079  break;
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));
1084  break;
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));
1090  break;
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));
1096  break;
1097  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING:
1098  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING:
1099  {
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);
1107  }
1108  }
1109  break;
1110  case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE:
1111  {
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);
1115  }
1116  }
1117  break;
1118  default:
1119  throw std::runtime_error("unknown type");
1120  }
1121  }
1122 
1123  return current_alignment - initial_alignment;
1124 }
1125 
1126 template<typename MembersType>
1128  const void * ros_message, const void * impl) const
1129 {
1130  if (max_size_bound_) {
1131  return m_typeSize;
1132  }
1133 
1134  assert(ros_message);
1135  assert(members_);
1136 
1137  // Encapsulation size
1138  size_t ret_val = 4;
1139 
1140  (void)impl;
1141  if (members_->member_count_ != 0) {
1142  ret_val += TypeSupport::getEstimatedSerializedSize(members_, ros_message, 0);
1143  } else {
1144  ret_val += 1;
1145  }
1146 
1147  return ret_val;
1148 }
1149 
1150 template<typename MembersType>
1152  const void * ros_message, eprosima::fastcdr::Cdr & ser, const void * impl) const
1153 {
1154  assert(ros_message);
1155  assert(members_);
1156 
1157  // Serialize encapsulation
1158  ser.serialize_encapsulation();
1159 
1160  (void)impl;
1161  if (members_->member_count_ != 0) {
1162  TypeSupport::serializeROSmessage(ser, members_, ros_message);
1163  } else {
1164  ser << (uint8_t)0;
1165  }
1166 
1167  return true;
1168 }
1169 
1170 template<typename MembersType>
1172  eprosima::fastcdr::Cdr & deser, void * ros_message, const void * impl) const
1173 {
1174  assert(ros_message);
1175  assert(members_);
1176 
1177  // Deserialize encapsulation.
1178  deser.read_encapsulation();
1179 
1180  (void)impl;
1181  if (members_->member_count_ != 0) {
1182  TypeSupport::deserializeROSmessage(deser, members_, ros_message, false);
1183  } else {
1184  uint8_t dump = 0;
1185  deser >> dump;
1186  (void)dump;
1187  }
1188 
1189  return true;
1190 }
1191 
1192 } // namespace rmw_fastrtps_dynamic_cpp
1193 
1194 #endif // RMW_FASTRTPS_DYNAMIC_CPP__TYPESUPPORT_IMPL_HPP_
std::is_same
std::vector::resize
T resize(T... args)
rmw_fastrtps_dynamic_cpp::GenericCSequence
Definition: TypeSupport_impl.hpp:42
std::string
rmw_fastrtps_dynamic_cpp::StringHelper< rosidl_typesupport_introspection_c__MessageMembers >
Definition: TypeSupport.hpp:55
rmw_fastrtps_dynamic_cpp::BaseTypeSupport
Definition: TypeSupport.hpp:147
rmw_fastrtps_dynamic_cpp::TypeSupport
Definition: TypeSupport.hpp:166
std::vector
std::vector::size
T size(T... args)
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence
Definition: TypeSupport_impl.hpp:58
rmw_fastrtps_dynamic_cpp::next_field_align
size_t next_field_align(const rosidl_typesupport_introspection_c__MessageMember *member, void *field, size_t current_alignment)
Definition: TypeSupport_impl.hpp:535
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence__init
bool rosidl_runtime_c__void__Sequence__init(rosidl_runtime_c__void__Sequence *sequence, size_t size, size_t member_size)
Definition: TypeSupport_impl.hpp:69
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence::data
void * data
Definition: TypeSupport_impl.hpp:60
rmw_fastrtps_dynamic_cpp::next_field_align_string
size_t next_field_align_string(const rosidl_typesupport_introspection_c__MessageMember *member, void *field, size_t current_alignment)
TypeSupport.hpp
rmw_fastrtps_shared_cpp::TypeSupport::TypeSupport
TypeSupport()
TypeSupport< MembersType >::getEstimatedSerializedSize
virtual size_t getEstimatedSerializedSize(const void *ros_message, const void *impl) const =0
TypeSupport< MembersType >::serializeROSmessage
virtual bool serializeROSmessage(const void *ros_message, eprosima::fastcdr::Cdr &ser, const void *impl) const =0
rmw_fastrtps_dynamic_cpp
Definition: get_client.hpp:23
std::vector::push_back
T push_back(T... args)
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence::capacity
size_t capacity
The number of allocated items in data.
Definition: TypeSupport_impl.hpp:64
TypeSupport< MembersType >::deserializeROSmessage
virtual bool deserializeROSmessage(eprosima::fastcdr::Cdr &deser, void *ros_message, const void *impl) const =0
macros.hpp
std::string::c_str
T c_str(T... args)
std::runtime_error
rmw_fastrtps_dynamic_cpp::deserialize_field
void deserialize_field(const rosidl_typesupport_introspection_c__MessageMember *member, void *field, eprosima::fastcdr::Cdr &deser, bool call_new)
Definition: TypeSupport_impl.hpp:812
rmw_fastrtps_dynamic_cpp::get_submessage_array_deserialize
size_t get_submessage_array_deserialize(const rosidl_typesupport_introspection_c__MessageMember *member, eprosima::fastcdr::Cdr &deser, void *field, void *&subros_message, bool, size_t sub_members_size, size_t)
Definition: TypeSupport_impl.hpp:936
rmw_fastrtps_dynamic_cpp::serialize_field
void serialize_field(const rosidl_typesupport_introspection_c__MessageMember *member, void *field, eprosima::fastcdr::Cdr &ser)
Definition: TypeSupport_impl.hpp:259
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence
struct rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence rosidl_runtime_c__void__Sequence
rmw_fastrtps_dynamic_cpp::get_array_size_and_assign_field
size_t get_array_size_and_assign_field(const rosidl_typesupport_introspection_c__MessageMember *member, void *field, void *&subros_message, size_t, size_t)
Definition: TypeSupport_impl.hpp:360
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence__fini
void rosidl_runtime_c__void__Sequence__fini(rosidl_runtime_c__void__Sequence *sequence)
Definition: TypeSupport_impl.hpp:90
std::vector::empty
T empty(T... args)
SPECIALIZE_GENERIC_C_SEQUENCE
#define SPECIALIZE_GENERIC_C_SEQUENCE(C_NAME, C_TYPE)
Definition: macros.hpp:21
rmw_fastrtps_dynamic_cpp::rosidl_runtime_c__void__Sequence::size
size_t size
The number of valid items in data.
Definition: TypeSupport_impl.hpp:62
std::string::data
T data(T... args)