|
25 | 25 | #include "dynmsg/message_reading.hpp" |
26 | 26 | #include "dynmsg/string_utils.hpp" |
27 | 27 | #include "dynmsg/typesupport.hpp" |
28 | | -#include "dynmsg/vector_utils.hpp" |
29 | 28 |
|
30 | 29 | namespace dynmsg |
31 | 30 | { |
@@ -516,21 +515,13 @@ dynamic_array_to_yaml( |
516 | 515 | array_node); |
517 | 516 | break; |
518 | 517 | case rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE: |
519 | | - // We do not know the specific type of the sequence because the type is not available at |
520 | | - // compile-time, but we know it's a vector and we know the size of the contained type. |
521 | 518 | RosMessage_Cpp nested_member; |
522 | 519 | nested_member.type_info = reinterpret_cast<const TypeInfo_Cpp *>(member_info.members_->data); |
523 | | - uint8_t * element_data; |
524 | | - memcpy(&element_data, member_data, sizeof(void *)); |
525 | | - size_t element_size; |
526 | | - element_size = nested_member.type_info->size_of_; |
527 | | - size_t element_count; |
528 | | - element_count = dynmsg::get_vector_size(member_data, element_size); |
529 | | - DYNMSG_DEBUG(std::cout << "\telement_size=" << element_size << std::endl); |
530 | | - DYNMSG_DEBUG(std::cout << "\telement_count=" << element_count << std::endl); |
531 | | - for (size_t ii = 0; ii < element_count; ++ii) { |
532 | | - nested_member.data = element_data + ii * element_size; |
| 520 | + void * data; |
| 521 | + data = reinterpret_cast<void *>(const_cast<uint8_t *>(member_data)); |
| 522 | + for (size_t i = 0; i < member_info.size_function(data); i++) { |
533 | 523 | // Recursively read the nested type into the array element in the YAML representation |
| 524 | + nested_member.data = reinterpret_cast<uint8_t *>(member_info.get_function(data, i)); |
534 | 525 | array_node.push_back(message_to_yaml(nested_member)); |
535 | 526 | } |
536 | 527 | break; |
|
0 commit comments