diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/TypeSupport.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/TypeSupport.hpp index 7da7a0d64..df370b0f5 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/TypeSupport.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/TypeSupport.hpp @@ -104,6 +104,12 @@ class TypeSupport : public eprosima::fastdds::dds::TopicDataType return is_plain_; } + RMW_FASTRTPS_SHARED_CPP_PUBLIC + inline bool is_plain(eprosima::fastdds::dds::DataRepresentationId_t rep) const override + { + return is_plain_ && rep == eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION; + } + RMW_FASTRTPS_SHARED_CPP_PUBLIC virtual ~TypeSupport() {} diff --git a/rmw_fastrtps_shared_cpp/src/qos.cpp b/rmw_fastrtps_shared_cpp/src/qos.cpp index 6079cfda3..1b1506151 100644 --- a/rmw_fastrtps_shared_cpp/src/qos.cpp +++ b/rmw_fastrtps_shared_cpp/src/qos.cpp @@ -181,7 +181,15 @@ get_datareader_qos( const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataReaderQos & datareader_qos) { - return fill_data_entity_qos_from_profile(qos_policies, type_hash, datareader_qos); + if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datareader_qos)) { + // The type support in the RMW implementation is always XCDR1. + constexpr auto rep = eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION; + datareader_qos.type_consistency().representation.clear(); + datareader_qos.type_consistency().representation.m_value.push_back(rep); + return true; + } + + return false; } bool @@ -190,7 +198,15 @@ get_datawriter_qos( const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataWriterQos & datawriter_qos) { - return fill_data_entity_qos_from_profile(qos_policies, type_hash, datawriter_qos); + if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datawriter_qos)) { + // The type support in the RMW implementation is always XCDR1. + constexpr auto rep = eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION; + datawriter_qos.representation().clear(); + datawriter_qos.representation().m_value.push_back(rep); + return true; + } + + return false; } bool diff --git a/rmw_fastrtps_shared_cpp/test/test_rmw_qos_to_dds_attributes.cpp b/rmw_fastrtps_shared_cpp/test/test_rmw_qos_to_dds_attributes.cpp index 136ec993a..905a79e7c 100644 --- a/rmw_fastrtps_shared_cpp/test/test_rmw_qos_to_dds_attributes.cpp +++ b/rmw_fastrtps_shared_cpp/test/test_rmw_qos_to_dds_attributes.cpp @@ -103,6 +103,10 @@ TEST_F(GetDataReaderQoSTest, nominal_conversion) { eprosima::fastdds::dds::KEEP_LAST_HISTORY_QOS, subscriber_qos_.history().kind); EXPECT_GE(10, subscriber_qos_.history().depth); + ASSERT_EQ(1, subscriber_qos_.type_consistency().representation.m_value.size()); + EXPECT_EQ( + eprosima::fastdds::dds::DataRepresentationId::XCDR_DATA_REPRESENTATION, + subscriber_qos_.type_consistency().representation.m_value[0]); } TEST_F(GetDataReaderQoSTest, large_depth_conversion) { @@ -201,6 +205,10 @@ TEST_F(GetDataWriterQoSTest, nominal_conversion) { eprosima::fastdds::dds::KEEP_LAST_HISTORY_QOS, publisher_qos_.history().kind); EXPECT_GE(10, publisher_qos_.history().depth); + ASSERT_EQ(1, publisher_qos_.representation().m_value.size()); + EXPECT_EQ( + eprosima::fastdds::dds::DataRepresentationId::XCDR_DATA_REPRESENTATION, + publisher_qos_.representation().m_value[0]); } TEST_F(GetDataWriterQoSTest, large_depth_conversion) {