From 3684d17b1001adc10cc5e217f9dadc8a1c5e8d05 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 01:00:24 +0800 Subject: [PATCH 1/8] Add support for best available QoS Signed-off-by: Michael X. Grey --- rclrs/src/qos.rs | 190 +++++++++++++++++++++++++++++++++++++- rclrs/src/subscription.rs | 46 +++++++++ 2 files changed, 235 insertions(+), 1 deletion(-) diff --git a/rclrs/src/qos.rs b/rclrs/src/qos.rs index dcaa0b30f..f24847932 100644 --- a/rclrs/src/qos.rs +++ b/rclrs/src/qos.rs @@ -1,6 +1,9 @@ use std::time::Duration; -use crate::rcl_bindings::*; +use crate::{ + rcl_bindings::*, + log_error, +}; /// The `HISTORY` DDS QoS policy. /// @@ -61,6 +64,9 @@ pub enum QoSReliabilityPolicy { Reliable = 1, /// Send messages but do not guarantee delivery. BestEffort = 2, + /// Use the highest level of service among the majority of endpoints currently available. + #[cfg(not(ros_distro = "humble"))] + BestAvailable = 4, } /// The `DURABILITY` DDS QoS policy. @@ -88,6 +94,9 @@ pub enum QoSDurabilityPolicy { TransientLocal = 1, /// Do not retain/request old messages. Volatile = 2, + /// Use the highest level of service among the majority of endpoints currently available. + #[cfg(not(ros_distro = "humble"))] + BestAvailable = 4, } /// The `LIVELINESS` DDS QoS policy. @@ -113,6 +122,9 @@ pub enum QoSLivelinessPolicy { /// on the topic or an explicit signal from the application to assert liveliness on the topic /// will mark the topic as being alive. ManualByTopic = 3, + /// Use the highest level of service among the majority of endpoints currently available. + #[cfg(not(ros_distro = "humble"))] + BestAvailable = 5, } /// A duration that can take two special values: System default and infinite. @@ -206,6 +218,40 @@ impl From for rmw_qos_profile_t { } } +impl From<&rmw_qos_profile_t> for QoSProfile { + fn from(profile: &rmw_qos_profile_t) -> Self { + let history = match profile.history { + rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT => { + QoSHistoryPolicy::SystemDefault { depth: profile.depth as u32 } + } + rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_KEEP_LAST => { + QoSHistoryPolicy::KeepLast { depth: profile.depth as u32 } + } + rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_KEEP_ALL => { + QoSHistoryPolicy::KeepAll + } + rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_UNKNOWN => { + log_error!( + "QoSProfile.conversion", + "History policy is unknown. Converting as KeepLast.", + ); + QoSHistoryPolicy::KeepLast { depth: profile.depth as u32 } + } + }; + + QoSProfile { + history, + reliability: (&profile.reliability).into(), + durability: (&profile.durability).into(), + deadline: (&profile.deadline).into(), + lifespan: (&profile.lifespan).into(), + liveliness: (&profile.liveliness).into(), + liveliness_lease: (&profile.liveliness_lease_duration).into(), + avoid_ros_namespace_conventions: profile.avoid_ros_namespace_conventions, + } + } +} + impl QoSProfile { /// Sets the QoS profile history to [QoSHistoryPolicy::KeepLast] with the specified depth. pub fn keep_last(mut self, depth: u32) -> Self { @@ -300,6 +346,23 @@ impl QoSProfile { pub fn action_status_default() -> Self { QOS_PROFILE_ACTION_STATUS_DEFAULT } + + /// Match the highest level service of the majority of endpoints available + /// when the primitive (publisher or subscription) is created. + /// + /// From rclcpp documentation: + /// > The middleware is not expected to update policies after creating a + /// > subscription or publisher, even if one or more policies are incompatible + /// > with newly discovered endpoints. Therefore, this profile should be used + /// > with care since non-deterministic behavior can occur due to races with + /// > discovery. + pub fn best_available() -> Self { + unsafe { + // SAFETY: There are no preconditions for using this static const + // global variable + (&rmw_qos_profile_best_available).into() + } + } } impl From for rmw_qos_history_policy_t { @@ -328,6 +391,37 @@ impl From for rmw_qos_reliability_policy_t { QoSReliabilityPolicy::BestEffort => { rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT } + #[cfg(not(ros_distro = "humble"))] + QoSReliabilityPolicy::BestAvailable => { + rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE + } + } + } +} + +impl From<&rmw_qos_reliability_policy_t> for QoSReliabilityPolicy { + fn from(policy: &rmw_qos_reliability_policy_t) -> Self { + match policy { + rmw_qos_reliability_policy_e::RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT => { + QoSReliabilityPolicy::SystemDefault + } + rmw_qos_reliability_policy_e::RMW_QOS_POLICY_RELIABILITY_RELIABLE => { + QoSReliabilityPolicy::Reliable + } + rmw_qos_reliability_policy_e::RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT => { + QoSReliabilityPolicy::BestEffort + } + #[cfg(not(ros_distro = "humble"))] + rmw_qos_reliability_policy_e::RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE => { + QoSReliabilityPolicy::BestAvailable + } + rmw_qos_reliability_policy_e::RMW_QOS_POLICY_RELIABILITY_UNKNOWN => { + log_error!( + "QoSReliabilityPolicy.conversion", + "Reliability policy is unknown. Converting as SystemDefault", + ); + QoSReliabilityPolicy::SystemDefault + } } } } @@ -344,6 +438,37 @@ impl From for rmw_qos_durability_policy_t { QoSDurabilityPolicy::Volatile => { rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_VOLATILE } + #[cfg(not(ros_distro = "humble"))] + QoSDurabilityPolicy::BestAvailable => { + rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE + } + } + } +} + +impl From<&rmw_qos_durability_policy_t> for QoSDurabilityPolicy { + fn from(policy: &rmw_qos_durability_policy_t) -> Self { + match policy { + rmw_qos_durability_policy_e::RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT => { + QoSDurabilityPolicy::SystemDefault + } + rmw_qos_durability_policy_e::RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL => { + QoSDurabilityPolicy::TransientLocal + } + rmw_qos_durability_policy_e::RMW_QOS_POLICY_DURABILITY_VOLATILE => { + QoSDurabilityPolicy::Volatile + } + #[cfg(not(ros_distro = "humble"))] + rmw_qos_durability_policy_e::RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE => { + QoSDurabilityPolicy::BestAvailable + } + rmw_qos_durability_policy_e::RMW_QOS_POLICY_DURABILITY_UNKNOWN => { + log_error!( + "QoSDurabilityPolicy.conversion", + "Durability policy is unknown. Converting as SystemDefault.", + ); + QoSDurabilityPolicy::SystemDefault + } } } } @@ -360,6 +485,42 @@ impl From for rmw_qos_liveliness_policy_t { QoSLivelinessPolicy::ManualByTopic => { rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC } + QoSLivelinessPolicy::BestAvailable => { + rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE + } + } + } +} + +impl From<&rmw_qos_liveliness_policy_t> for QoSLivelinessPolicy { + fn from(value: &rmw_qos_liveliness_policy_t) -> Self { + match value { + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT => { + QoSLivelinessPolicy::SystemDefault + } + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_AUTOMATIC => { + QoSLivelinessPolicy::Automatic + } + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC => { + QoSLivelinessPolicy::ManualByTopic + } + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE => { + QoSLivelinessPolicy::BestAvailable + } + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE => { + log_error!( + "QoSLivelinessPolicy.conversion", + "Using deprecated liveliness mode. Converting as ManualByTopic.", + ); + QoSLivelinessPolicy::ManualByTopic + } + rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_UNKNOWN => { + log_error!( + "QoSLivelinessPolicy.conversion", + "Liveliness policy is unknown. Converting as SystemDefault.", + ); + QoSLivelinessPolicy::SystemDefault + } } } } @@ -385,6 +546,33 @@ impl From for rmw_time_t { } } +impl From<&rmw_time_t> for Duration { + fn from(value: &rmw_time_t) -> Self { + Duration::from_secs(value.sec) + Duration::from_nanos(value.nsec) + } +} + +impl From<&rmw_time_t> for QoSDuration { + fn from(value: &rmw_time_t) -> Self { + let value: Duration = value.into(); + let time_eq = |a: Duration, b: QoSDuration| { + let b: rmw_time_t = b.into(); + let b: Duration = (&b).into(); + a == b + }; + + if time_eq(value, QoSDuration::SystemDefault) { + return QoSDuration::SystemDefault; + } + + if time_eq(value, QoSDuration::Infinite) { + return QoSDuration::Infinite; + } + + QoSDuration::Custom(value) + } +} + /// Equivalent to `rmw_qos_profile_sensor_data` from the [`rmw` package][1]. /// /// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index 06d331eb8..edf89c9ab 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -10,6 +10,7 @@ use crate::{ error::ToResult, qos::QoSProfile, rcl_bindings::*, IntoPrimitiveOptions, Node, NodeHandle, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, Waitable, WaitableLifecycle, WorkScope, Worker, WorkerCommands, ENTITY_LIFECYCLE_MUTEX, + log_error, }; mod any_subscription_callback; @@ -110,6 +111,27 @@ where .into_owned() } + /// Returns the QoS settings of the subscription. + pub fn qos(&self) -> QoSProfile { + let options = unsafe { + // SAFETY: The handle is protected by a mutex. No other + // preconditions need to be met. + let handle = self.handle.lock(); + let options = rcl_subscription_get_options(&*handle); + if options.is_null() { + None + } else { + Some((&(*options).qos).into()) + } + }; + + if options.is_none() { + log_error!("Subscroption.qos", "Options returned null"); + } + + options.unwrap_or_default() + } + /// Used by [`Node`][crate::Node] to create a new subscription. pub(crate) fn create<'a>( options: impl Into>, @@ -592,4 +614,28 @@ mod tests { let message_was_received = success.load(Ordering::Acquire); assert!(message_was_received); } + + #[test] + fn test_subscription_qos_settings() { + use crate::*; + use crate::vendor::example_interfaces::msg::Empty; + + let executor = Context::default().create_basic_executor(); + + let node = executor + .create_node(&format!("test_subscription_qos_settings_{}", line!())) + .unwrap(); + + let subscription = node.create_subscription( + "test_subscription_qos_topic" + .best_effort(), + |_: Empty| { + // Do nothing + } + ) + .unwrap(); + + let qos = subscription.qos(); + assert!(matches!(qos.reliability, QoSReliabilityPolicy::BestEffort)); + } } From f797c5c667c8fae62a439d40a58dc4098567aaa0 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 01:16:29 +0800 Subject: [PATCH 2/8] Remember to suppress BestAvailable for humble Signed-off-by: Michael X. Grey --- rclrs/src/qos.rs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/rclrs/src/qos.rs b/rclrs/src/qos.rs index f24847932..b3e0e199a 100644 --- a/rclrs/src/qos.rs +++ b/rclrs/src/qos.rs @@ -356,6 +356,7 @@ impl QoSProfile { /// > with newly discovered endpoints. Therefore, this profile should be used /// > with care since non-deterministic behavior can occur due to races with /// > discovery. + #[cfg(not(ros_distro = "humble"))] pub fn best_available() -> Self { unsafe { // SAFETY: There are no preconditions for using this static const @@ -485,6 +486,7 @@ impl From for rmw_qos_liveliness_policy_t { QoSLivelinessPolicy::ManualByTopic => { rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC } + #[cfg(not(ros_distro = "humble"))] QoSLivelinessPolicy::BestAvailable => { rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE } @@ -504,6 +506,7 @@ impl From<&rmw_qos_liveliness_policy_t> for QoSLivelinessPolicy { rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC => { QoSLivelinessPolicy::ManualByTopic } + #[cfg(not(ros_distro = "humble"))] rmw_qos_liveliness_policy_e::RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE => { QoSLivelinessPolicy::BestAvailable } From 0b97f768fbf4e7a8fe21a79c0508c1dbeec7d0a9 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 01:22:22 +0800 Subject: [PATCH 3/8] Fix style Signed-off-by: Michael X. Grey --- rclrs/src/qos.rs | 21 +++++++++++---------- rclrs/src/subscription.rs | 20 ++++++++------------ 2 files changed, 19 insertions(+), 22 deletions(-) diff --git a/rclrs/src/qos.rs b/rclrs/src/qos.rs index b3e0e199a..ba056a630 100644 --- a/rclrs/src/qos.rs +++ b/rclrs/src/qos.rs @@ -1,9 +1,6 @@ use std::time::Duration; -use crate::{ - rcl_bindings::*, - log_error, -}; +use crate::{log_error, rcl_bindings::*}; /// The `HISTORY` DDS QoS policy. /// @@ -222,20 +219,24 @@ impl From<&rmw_qos_profile_t> for QoSProfile { fn from(profile: &rmw_qos_profile_t) -> Self { let history = match profile.history { rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT => { - QoSHistoryPolicy::SystemDefault { depth: profile.depth as u32 } + QoSHistoryPolicy::SystemDefault { + depth: profile.depth as u32, + } } rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_KEEP_LAST => { - QoSHistoryPolicy::KeepLast { depth: profile.depth as u32 } - } - rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_KEEP_ALL => { - QoSHistoryPolicy::KeepAll + QoSHistoryPolicy::KeepLast { + depth: profile.depth as u32, + } } + rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_KEEP_ALL => QoSHistoryPolicy::KeepAll, rmw_qos_history_policy_e::RMW_QOS_POLICY_HISTORY_UNKNOWN => { log_error!( "QoSProfile.conversion", "History policy is unknown. Converting as KeepLast.", ); - QoSHistoryPolicy::KeepLast { depth: profile.depth as u32 } + QoSHistoryPolicy::KeepLast { + depth: profile.depth as u32, + } } }; diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index edf89c9ab..b74449965 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -7,10 +7,9 @@ use std::{ use rosidl_runtime_rs::{Message, RmwMessage}; use crate::{ - error::ToResult, qos::QoSProfile, rcl_bindings::*, IntoPrimitiveOptions, Node, NodeHandle, - RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, Waitable, - WaitableLifecycle, WorkScope, Worker, WorkerCommands, ENTITY_LIFECYCLE_MUTEX, - log_error, + error::ToResult, log_error, qos::QoSProfile, rcl_bindings::*, IntoPrimitiveOptions, Node, + NodeHandle, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, + Waitable, WaitableLifecycle, WorkScope, Worker, WorkerCommands, ENTITY_LIFECYCLE_MUTEX, }; mod any_subscription_callback; @@ -617,8 +616,8 @@ mod tests { #[test] fn test_subscription_qos_settings() { - use crate::*; use crate::vendor::example_interfaces::msg::Empty; + use crate::*; let executor = Context::default().create_basic_executor(); @@ -626,14 +625,11 @@ mod tests { .create_node(&format!("test_subscription_qos_settings_{}", line!())) .unwrap(); - let subscription = node.create_subscription( - "test_subscription_qos_topic" - .best_effort(), - |_: Empty| { + let subscription = node + .create_subscription("test_subscription_qos_topic".best_effort(), |_: Empty| { // Do nothing - } - ) - .unwrap(); + }) + .unwrap(); let qos = subscription.qos(); assert!(matches!(qos.reliability, QoSReliabilityPolicy::BestEffort)); From 45b034d66d6d79433151405672c14770312b87aa Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 01:29:27 +0800 Subject: [PATCH 4/8] Add a test that uses .qos Signed-off-by: Michael X. Grey --- rclrs/src/subscription.rs | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index b74449965..d5b298636 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -632,6 +632,21 @@ mod tests { .unwrap(); let qos = subscription.qos(); - assert!(matches!(qos.reliability, QoSReliabilityPolicy::BestEffort)); + assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); + + let expected_qos = QoSProfile::topics_default().best_effort(); + assert_eq!(expected_qos.reliability, QoSReliabilityPolicy::BestEffort); + let subscription = node + .create_subscription( + "test_subscription_qos_topic_2".qos(expected_qos), + |_: Empty| { + // Do nothing + }, + ) + .unwrap(); + + let qos = subscription.qos(); + assert_eq!(expected_qos.reliability, qos.reliability); + assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); } } From 770c195da8bbc941f6dcd9fbc9ebf0f0e0fa22ad Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 01:31:12 +0800 Subject: [PATCH 5/8] Add a test that sets SubscriptionOptions directly Signed-off-by: Michael X. Grey --- rclrs/src/subscription.rs | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index d5b298636..b47d57aee 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -648,5 +648,21 @@ mod tests { let qos = subscription.qos(); assert_eq!(expected_qos.reliability, qos.reliability); assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); + + let subscription = node + .create_subscription( + SubscriptionOptions { + topic: "test_subscription_qos_topic_3", + qos: expected_qos, + }, + |_: Empty| { + // Do nothing + }, + ) + .unwrap(); + + let qos = subscription.qos(); + assert_eq!(expected_qos.reliability, qos.reliability); + assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); } } From 0e95346f5102cf3a96b2d783a450b2ce30ee8b86 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 13:09:10 +0800 Subject: [PATCH 6/8] Add a test for setting reliability based on parameters Signed-off-by: Michael X. Grey --- rclrs/src/subscription.rs | 49 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index b47d57aee..ad2f8d05c 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -665,4 +665,53 @@ mod tests { assert_eq!(expected_qos.reliability, qos.reliability); assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); } + + #[test] + fn test_setting_qos_from_parameters() { + use crate::vendor::example_interfaces::msg::Empty; + use crate::*; + + let args = [ + "--ros-args", + "-p", + "qos_reliability:=best_effort", + ].map(ToString::to_string); + + let context = Context::new(args, InitOptions::default()).unwrap(); + + let executor = context.create_basic_executor(); + + let node = executor + .create_node(&format!("test_setting_qos_from_parameters_{}", line!())) + .unwrap(); + + let qos_reliability_str = node + .declare_parameter::>("qos_reliability") + .default("best_effort".into()) + .mandatory() + .unwrap() + .get(); + + let mut expected_qos = QOS_PROFILE_DEFAULT; + expected_qos.reliability = match &*qos_reliability_str { + "reliable" => QoSReliabilityPolicy::Reliable, + "best_effort" => QoSReliabilityPolicy::BestEffort, + "best_available" => QoSReliabilityPolicy::BestAvailable, + x => panic!("unknown reliability string: {x}"), + }; + + assert_eq!(expected_qos.reliability, QoSReliabilityPolicy::BestEffort); + let subscription = node + .create_subscription( + "test_setting_qos_from_parameters_topic".qos(expected_qos), + |_: Empty| { + // Do nothing + } + ) + .unwrap(); + + let qos = subscription.qos(); + assert_eq!(expected_qos.reliability, qos.reliability); + assert_eq!(qos.reliability, QoSReliabilityPolicy::BestEffort); + } } From de1fb51e7e0080c99e073bfaadbc5aa2fa2e88d1 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 13:19:07 +0800 Subject: [PATCH 7/8] Fix style Signed-off-by: Michael X. Grey --- rclrs/src/subscription.rs | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index ad2f8d05c..966fac05e 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -671,11 +671,7 @@ mod tests { use crate::vendor::example_interfaces::msg::Empty; use crate::*; - let args = [ - "--ros-args", - "-p", - "qos_reliability:=best_effort", - ].map(ToString::to_string); + let args = ["--ros-args", "-p", "qos_reliability:=best_effort"].map(ToString::to_string); let context = Context::new(args, InitOptions::default()).unwrap(); @@ -706,7 +702,7 @@ mod tests { "test_setting_qos_from_parameters_topic".qos(expected_qos), |_: Empty| { // Do nothing - } + }, ) .unwrap(); From 2b0a889d1a3a9b04031d6147953cf2b883c66b9e Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Nov 2025 13:34:03 +0800 Subject: [PATCH 8/8] Remember to suppress BestAvailable for humble Signed-off-by: Michael X. Grey --- rclrs/src/subscription.rs | 1 + 1 file changed, 1 insertion(+) diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index 966fac05e..dd32ee099 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -692,6 +692,7 @@ mod tests { expected_qos.reliability = match &*qos_reliability_str { "reliable" => QoSReliabilityPolicy::Reliable, "best_effort" => QoSReliabilityPolicy::BestEffort, + #[cfg(not(ros_distro = "humble"))] "best_available" => QoSReliabilityPolicy::BestAvailable, x => panic!("unknown reliability string: {x}"), };