diff --git a/rmw_fastrtps_cpp/src/publisher.cpp b/rmw_fastrtps_cpp/src/publisher.cpp index da9de0eb3..a93deeb87 100644 --- a/rmw_fastrtps_cpp/src/publisher.cpp +++ b/rmw_fastrtps_cpp/src/publisher.cpp @@ -256,7 +256,7 @@ rmw_fastrtps_cpp::create_publisher( } // Get QoS from RMW - if (!get_datawriter_qos(*qos_policies, writer_qos)) { + if (!get_datawriter_qos(*qos_policies, *type_supports->type_hash, writer_qos)) { RMW_SET_ERROR_MSG("create_publisher() failed setting data writer QoS"); return nullptr; } diff --git a/rmw_fastrtps_cpp/src/rmw_client.cpp b/rmw_fastrtps_cpp/src/rmw_client.cpp index aa8c23b17..70a126ee0 100644 --- a/rmw_fastrtps_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_cpp/src/rmw_client.cpp @@ -314,7 +314,9 @@ rmw_create_client( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(adapted_qos_policies, reader_qos)) { + if (!get_datareader_qos( + adapted_qos_policies, *type_supports->response_typesupport->type_hash, reader_qos)) + { RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS"); return nullptr; } @@ -368,7 +370,9 @@ rmw_create_client( writer_qos.data_sharing().off(); } - if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) { + if (!get_datawriter_qos( + adapted_qos_policies, *type_supports->request_typesupport->type_hash, writer_qos)) + { RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS"); return nullptr; } diff --git a/rmw_fastrtps_cpp/src/rmw_service.cpp b/rmw_fastrtps_cpp/src/rmw_service.cpp index 36767afdd..ed8cf4fa0 100644 --- a/rmw_fastrtps_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_cpp/src/rmw_service.cpp @@ -313,7 +313,9 @@ rmw_create_service( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(adapted_qos_policies, reader_qos)) { + if (!get_datareader_qos( + adapted_qos_policies, *type_supports->request_typesupport->type_hash, reader_qos)) + { RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS"); return nullptr; } @@ -371,7 +373,9 @@ rmw_create_service( writer_qos.data_sharing().off(); } - if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) { + if (!get_datawriter_qos( + adapted_qos_policies, *type_supports->response_typesupport->type_hash, writer_qos)) + { RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS"); return nullptr; } diff --git a/rmw_fastrtps_cpp/src/subscription.cpp b/rmw_fastrtps_cpp/src/subscription.cpp index 9ce7ac111..a367c7626 100644 --- a/rmw_fastrtps_cpp/src/subscription.cpp +++ b/rmw_fastrtps_cpp/src/subscription.cpp @@ -280,7 +280,7 @@ create_subscription( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(*qos_policies, reader_qos)) { + if (!get_datareader_qos(*qos_policies, *type_supports->type_hash, reader_qos)) { RMW_SET_ERROR_MSG("create_subscription() failed setting data reader QoS"); return nullptr; } diff --git a/rmw_fastrtps_dynamic_cpp/src/publisher.cpp b/rmw_fastrtps_dynamic_cpp/src/publisher.cpp index cae4a7a13..6aa6f04bc 100644 --- a/rmw_fastrtps_dynamic_cpp/src/publisher.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/publisher.cpp @@ -262,7 +262,7 @@ rmw_fastrtps_dynamic_cpp::create_publisher( } // Get QoS from RMW - if (!get_datawriter_qos(*qos_policies, writer_qos)) { + if (!get_datawriter_qos(*qos_policies, *type_supports->type_hash, writer_qos)) { RMW_SET_ERROR_MSG("create_publisher() failed setting data writer QoS"); return nullptr; } diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp index 3731f850f..5ba119381 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp @@ -345,7 +345,9 @@ rmw_create_client( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(adapted_qos_policies, reader_qos)) { + if (!get_datareader_qos( + adapted_qos_policies, *type_supports->response_typesupport->type_hash, reader_qos)) + { RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS"); return nullptr; } @@ -399,7 +401,9 @@ rmw_create_client( writer_qos.data_sharing().off(); } - if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) { + if (!get_datawriter_qos( + adapted_qos_policies, *type_supports->request_typesupport->type_hash, writer_qos)) + { RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS"); return nullptr; } diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp index 6b5486ff9..0ae48d98d 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp @@ -344,7 +344,9 @@ rmw_create_service( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(adapted_qos_policies, reader_qos)) { + if (!get_datareader_qos( + adapted_qos_policies, *type_supports->request_typesupport->type_hash, reader_qos)) + { RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS"); return nullptr; } @@ -402,7 +404,9 @@ rmw_create_service( writer_qos.data_sharing().off(); } - if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) { + if (!get_datawriter_qos( + adapted_qos_policies, *type_supports->response_typesupport->type_hash, writer_qos)) + { RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS"); return nullptr; } diff --git a/rmw_fastrtps_dynamic_cpp/src/subscription.cpp b/rmw_fastrtps_dynamic_cpp/src/subscription.cpp index fc147c0fe..511ffb9a9 100644 --- a/rmw_fastrtps_dynamic_cpp/src/subscription.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/subscription.cpp @@ -32,6 +32,8 @@ #include "rmw/rmw.h" #include "rmw/validate_full_topic_name.h" +#include "rosidl_runtime_c/type_hash.h" + #include "rcpputils/scope_exit.hpp" #include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp" @@ -264,7 +266,7 @@ create_subscription( reader_qos.data_sharing().off(); } - if (!get_datareader_qos(*qos_policies, reader_qos)) { + if (!get_datareader_qos(*qos_policies, *type_supports->type_hash, reader_qos)) { RMW_SET_ERROR_MSG("create_subscription() failed setting data reader QoS"); return nullptr; } diff --git a/rmw_fastrtps_shared_cpp/CMakeLists.txt b/rmw_fastrtps_shared_cpp/CMakeLists.txt index 7c5b196dc..6890a9519 100644 --- a/rmw_fastrtps_shared_cpp/CMakeLists.txt +++ b/rmw_fastrtps_shared_cpp/CMakeLists.txt @@ -39,6 +39,7 @@ find_package(ament_cmake_ros REQUIRED) find_package(rcpputils REQUIRED) find_package(rcutils REQUIRED) find_package(rmw_dds_common REQUIRED) +find_package(rosidl_runtime_c REQUIRED) find_package(rosidl_typesupport_introspection_c REQUIRED) find_package(rosidl_typesupport_introspection_cpp REQUIRED) find_package(tracetools REQUIRED) diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp index 0f3013ce5..36b710301 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp @@ -40,6 +40,7 @@ #include "rmw/rmw.h" #include "rmw_dds_common/context.hpp" +#include "rmw_dds_common/qos.hpp" #include "rmw_fastrtps_shared_cpp/create_rmw_gid.hpp" #include "rmw_fastrtps_shared_cpp/custom_event_info.hpp" @@ -205,12 +206,28 @@ class ParticipantListener : public eprosima::fastdds::dds::DomainParticipantList rmw_qos_profile_t qos_profile = rmw_qos_profile_unknown; rtps_qos_to_rmw_qos(proxyData.m_qos, &qos_profile); + const auto & userDataValue = proxyData.m_qos.m_userData.getValue(); + rosidl_type_hash_t type_hash; + if (RMW_RET_OK != rmw_dds_common::parse_type_hash_from_user_data( + userDataValue.data(), userDataValue.size(), type_hash)) + { + RCUTILS_LOG_WARN_NAMED( + "rmw_fastrtps_shared_cpp", + "Failed to parse type hash for topic '%s' with type '%s' from USER_DATA '%*s'.", + proxyData.topicName().c_str(), + proxyData.typeName().c_str(), + static_cast(userDataValue.size()), + reinterpret_cast(userDataValue.data())); + type_hash = rosidl_get_zero_initialized_type_hash(); + } + context->graph_cache.add_entity( rmw_fastrtps_shared_cpp::create_rmw_gid( identifier_, proxyData.guid()), proxyData.topicName().to_string(), proxyData.typeName().to_string(), + type_hash, rmw_fastrtps_shared_cpp::create_rmw_gid( identifier_, iHandle2GUID(proxyData.RTPSParticipantKey())), diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/qos.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/qos.hpp index ad5799452..694745b35 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/qos.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/qos.hpp @@ -27,6 +27,8 @@ #include "rmw_fastrtps_shared_cpp/visibility_control.h" +#include "rosidl_runtime_c/type_hash.h" + RMW_FASTRTPS_SHARED_CPP_PUBLIC bool is_valid_qos(const rmw_qos_profile_t & qos_policies); @@ -35,12 +37,14 @@ RMW_FASTRTPS_SHARED_CPP_PUBLIC bool get_datareader_qos( const rmw_qos_profile_t & qos_policies, + const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataReaderQos & reader_qos); RMW_FASTRTPS_SHARED_CPP_PUBLIC bool get_datawriter_qos( const rmw_qos_profile_t & qos_policies, + const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataWriterQos & writer_qos); RMW_FASTRTPS_SHARED_CPP_PUBLIC diff --git a/rmw_fastrtps_shared_cpp/package.xml b/rmw_fastrtps_shared_cpp/package.xml index 5a04ea49e..e0b5dc3c8 100644 --- a/rmw_fastrtps_shared_cpp/package.xml +++ b/rmw_fastrtps_shared_cpp/package.xml @@ -27,6 +27,7 @@ rcutils rmw rmw_dds_common + rosidl_runtime_c rosidl_typesupport_introspection_c rosidl_typesupport_introspection_cpp tracetools diff --git a/rmw_fastrtps_shared_cpp/src/qos.cpp b/rmw_fastrtps_shared_cpp/src/qos.cpp index 74464b778..1adae0bba 100644 --- a/rmw_fastrtps_shared_cpp/src/qos.cpp +++ b/rmw_fastrtps_shared_cpp/src/qos.cpp @@ -13,6 +13,9 @@ // limitations under the License. #include +#include + +#include "rcutils/logging_macros.h" #include "rmw_fastrtps_shared_cpp/qos.hpp" @@ -22,6 +25,10 @@ #include "rmw/error_handling.h" +#include "rmw_dds_common/qos.hpp" + +#include "rosidl_runtime_c/type_hash.h" + #include "time_utils.hpp" static @@ -142,20 +149,45 @@ bool fill_entity_qos_from_profile( return true; } +template +bool +fill_data_entity_qos_from_profile( + const rmw_qos_profile_t & qos_policies, + const rosidl_type_hash_t & type_hash, + DDSEntityQos & entity_qos) +{ + if (!fill_entity_qos_from_profile(qos_policies, entity_qos)) { + return false; + } + std::string user_data_str; + if (RMW_RET_OK != rmw_dds_common::encode_type_hash_for_user_data_qos(type_hash, user_data_str)) { + RCUTILS_LOG_WARN_NAMED( + "rmw_fastrtps_shared_cpp", + "Failed to encode type hash for topic, will not distribute it in USER_DATA."); + user_data_str.clear(); + } + std::vector user_data(user_data_str.begin(), user_data_str.end()); + entity_qos.user_data().resize(user_data.size()); + entity_qos.user_data().setValue(user_data); + return true; +} + bool get_datareader_qos( const rmw_qos_profile_t & qos_policies, + const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataReaderQos & datareader_qos) { - return fill_entity_qos_from_profile(qos_policies, datareader_qos); + return fill_data_entity_qos_from_profile(qos_policies, type_hash, datareader_qos); } bool get_datawriter_qos( const rmw_qos_profile_t & qos_policies, + const rosidl_type_hash_t & type_hash, eprosima::fastdds::dds::DataWriterQos & datawriter_qos) { - return fill_entity_qos_from_profile(qos_policies, datawriter_qos); + return fill_data_entity_qos_from_profile(qos_policies, type_hash, datawriter_qos); } 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 b080a1393..136ec993a 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 @@ -25,11 +25,15 @@ #include "rmw/error_handling.h" +#include "rosidl_runtime_c/type_hash.h" + using eprosima::fastdds::dds::DataReaderQos; static const eprosima::fastrtps::Duration_t InfiniteDuration = eprosima::fastrtps::rtps::c_RTPSTimeInfinite.to_duration_t(); +static const rosidl_type_hash_t zero_type_hash = rosidl_get_zero_initialized_type_hash(); + class GetDataReaderQoSTest : public ::testing::Test { protected: @@ -39,28 +43,28 @@ class GetDataReaderQoSTest : public ::testing::Test TEST_F(GetDataReaderQoSTest, test_unknown_history_policy_conversion_fails) { qos_profile_.history = RMW_QOS_POLICY_HISTORY_UNKNOWN; - EXPECT_FALSE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_FALSE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataReaderQoSTest, unknown_reliability_policy_conversion_fails) { qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN; - EXPECT_FALSE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_FALSE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataReaderQoSTest, unknown_durability_policy_conversion_fails) { qos_profile_.durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN; - EXPECT_FALSE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_FALSE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataReaderQoSTest, unknown_liveliness_policy_conversion_fails) { qos_profile_.liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN; - EXPECT_FALSE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_FALSE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } @@ -78,7 +82,7 @@ TEST_F(GetDataReaderQoSTest, nominal_conversion) { qos_profile_.liveliness_lease_duration.sec = 10u; qos_profile_.liveliness_lease_duration.nsec = 0u; - EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_TRUE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_EQ( eprosima::fastdds::dds::BEST_EFFORT_RELIABILITY_QOS, @@ -106,7 +110,7 @@ TEST_F(GetDataReaderQoSTest, large_depth_conversion) { qos_profile_.depth = depth; qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST; - EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_TRUE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_EQ( eprosima::fastdds::dds::KEEP_LAST_HISTORY_QOS, @@ -117,12 +121,12 @@ TEST_F(GetDataReaderQoSTest, large_depth_conversion) { constexpr size_t max_depth = static_cast(std::numeric_limits::max()); qos_profile_.depth = max_depth; - EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_TRUE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_LE(depth, static_cast(subscriber_qos_.history().depth)); if (max_depth < std::numeric_limits::max()) { qos_profile_.depth = max_depth + 1; - EXPECT_FALSE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_FALSE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); } } @@ -137,28 +141,28 @@ class GetDataWriterQoSTest : public ::testing::Test TEST_F(GetDataWriterQoSTest, test_unknown_history_policy_conversion_fails) { qos_profile_.history = RMW_QOS_POLICY_HISTORY_UNKNOWN; - EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_FALSE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataWriterQoSTest, unknown_reliability_policy_conversion_fails) { qos_profile_.reliability = RMW_QOS_POLICY_RELIABILITY_UNKNOWN; - EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_FALSE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataWriterQoSTest, unknown_durability_policy_conversion_fails) { qos_profile_.durability = RMW_QOS_POLICY_DURABILITY_UNKNOWN; - EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_FALSE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } TEST_F(GetDataWriterQoSTest, unknown_liveliness_policy_conversion_fails) { qos_profile_.liveliness = RMW_QOS_POLICY_LIVELINESS_UNKNOWN; - EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_FALSE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_TRUE(rmw_error_is_set()); rmw_reset_error(); } @@ -176,7 +180,7 @@ TEST_F(GetDataWriterQoSTest, nominal_conversion) { qos_profile_.liveliness_lease_duration.sec = 10u; qos_profile_.liveliness_lease_duration.nsec = 0u; - EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_TRUE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_EQ( eprosima::fastdds::dds::BEST_EFFORT_RELIABILITY_QOS, @@ -204,7 +208,7 @@ TEST_F(GetDataWriterQoSTest, large_depth_conversion) { qos_profile_.depth = depth; qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST; - EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_TRUE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_EQ( eprosima::fastdds::dds::KEEP_LAST_HISTORY_QOS, @@ -215,12 +219,12 @@ TEST_F(GetDataWriterQoSTest, large_depth_conversion) { constexpr size_t max_depth = static_cast(std::numeric_limits::max()); qos_profile_.depth = max_depth; - EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_TRUE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_LE(depth, static_cast(publisher_qos_.history().depth)); if (max_depth < std::numeric_limits::max()) { qos_profile_.depth = max_depth + 1; - EXPECT_FALSE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_FALSE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); } } @@ -229,7 +233,7 @@ TEST_F(GetDataReaderQoSTest, infinite_duration_conversions) qos_profile_.lifespan = RMW_DURATION_INFINITE; qos_profile_.deadline = RMW_DURATION_INFINITE; qos_profile_.liveliness_lease_duration = RMW_DURATION_INFINITE; - EXPECT_TRUE(get_datareader_qos(qos_profile_, subscriber_qos_)); + EXPECT_TRUE(get_datareader_qos(qos_profile_, zero_type_hash, subscriber_qos_)); EXPECT_EQ(subscriber_qos_.lifespan().duration, InfiniteDuration); EXPECT_EQ(subscriber_qos_.deadline().period, InfiniteDuration); EXPECT_EQ(subscriber_qos_.liveliness().lease_duration, InfiniteDuration); @@ -240,7 +244,7 @@ TEST_F(GetDataWriterQoSTest, infinite_duration_conversions) qos_profile_.lifespan = RMW_DURATION_INFINITE; qos_profile_.deadline = RMW_DURATION_INFINITE; qos_profile_.liveliness_lease_duration = RMW_DURATION_INFINITE; - EXPECT_TRUE(get_datawriter_qos(qos_profile_, publisher_qos_)); + EXPECT_TRUE(get_datawriter_qos(qos_profile_, zero_type_hash, publisher_qos_)); EXPECT_EQ(publisher_qos_.lifespan().duration, InfiniteDuration); EXPECT_EQ(publisher_qos_.deadline().period, InfiniteDuration); EXPECT_EQ(publisher_qos_.liveliness().lease_duration, InfiniteDuration);