From d5b8831a42ced22401cb2571ded48857b7339846 Mon Sep 17 00:00:00 2001 From: Todd Malsbary Date: Wed, 6 Nov 2019 13:36:41 -0800 Subject: [PATCH 1/2] Intra-process subscriber should use RMW actual qos. (ros2#913) Signed-off-by: Todd Malsbary --- rclcpp/include/rclcpp/subscription.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 81310d72c6..0234a00e3f 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -124,15 +124,16 @@ class Subscription : public SubscriptionBase using rclcpp::detail::resolve_intra_process_buffer_type; // Check if the QoS is compatible with intra-process. - if (qos.get_rmw_qos_profile().history == RMW_QOS_POLICY_HISTORY_KEEP_ALL) { + rmw_qos_profile_t qos_profile = get_actual_qos().get_rmw_qos_profile(); + if (qos_profile.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL) { throw std::invalid_argument( "intraprocess communication is not allowed with keep all history qos policy"); } - if (qos.get_rmw_qos_profile().depth == 0) { + if (qos_profile.depth == 0) { throw std::invalid_argument( "intraprocess communication is not allowed with 0 depth qos policy"); } - if (qos.get_rmw_qos_profile().durability != RMW_QOS_POLICY_DURABILITY_VOLATILE) { + if (qos_profile.durability != RMW_QOS_POLICY_DURABILITY_VOLATILE) { throw std::invalid_argument( "intraprocess communication allowed only with volatile durability"); } @@ -149,7 +150,7 @@ class Subscription : public SubscriptionBase options.get_allocator(), context, this->get_topic_name(), // important to get like this, as it has the fully-qualified name - qos.get_rmw_qos_profile(), + qos_profile, resolve_intra_process_buffer_type(options.intra_process_buffer_type, callback) ); From a951be40c7c174467a1a02fc74c3cfeab9c1437d Mon Sep 17 00:00:00 2001 From: Todd Malsbary Date: Wed, 20 Nov 2019 11:13:33 -0800 Subject: [PATCH 2/2] Remove keep_last_zero_depth_qos from invalid_qos_profiles. A depth of zero is defined as RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT, which is a valid QoS profile. Signed-off-by: Todd Malsbary --- rclcpp/test/test_subscription.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/rclcpp/test/test_subscription.cpp b/rclcpp/test/test_subscription.cpp index 78b420b3a0..5a4d334099 100644 --- a/rclcpp/test/test_subscription.cpp +++ b/rclcpp/test/test_subscription.cpp @@ -287,10 +287,6 @@ static std::vector invalid_qos_profiles() TestParameters( rclcpp::QoS(rclcpp::KeepAll()), "keep_all_qos")); - parameters.push_back( - TestParameters( - rclcpp::QoS(rclcpp::KeepLast(0)), - "keep_last_zero_depth_qos")); return parameters; }