do_not_use_testing_rclrs/qos.rs
1use std::time::Duration;
2
3use crate::rcl_bindings::*;
4
5/// The `HISTORY` DDS QoS policy.
6///
7/// A subscription internally maintains a queue of messages (called "samples" in DDS) that have not
8/// been processed yet by the application, and likewise a publisher internally maintains a queue.
9///
10/// If the history policy is `KeepAll`, this queue is unbounded, and if it is `KeepLast`, it is
11/// bounded and old values are discarded when the queue is overfull.
12///
13/// The `rmw` layer may not be able to handle very large queue depths, e.g. greater than
14/// `i32::MAX`.
15/// In this case, the functions taking the QoS profile as an argument will return an error.
16///
17/// # Compatibility
18/// | Publisher | Subscription | Compatible |
19/// | -- | -- | -- |
20/// | KeepLast | KeepLast | yes |
21/// | KeepLast | KeepAll | yes |
22/// | KeepAll | KeepLast | yes |
23/// | KeepAll | KeepAll | yes |
24///
25#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
26pub enum QoSHistoryPolicy {
27 /// Use the default policy of the RMW layer.
28 ///
29 /// If the default policy is `KeepAll`, the depth will be ignored.
30 SystemDefault {
31 /// The length of the publisher/subscription queue.
32 depth: u32,
33 },
34 /// Keep only the `depth` most recent messages.
35 KeepLast {
36 /// The length of the publisher/subscription queue.
37 depth: u32,
38 },
39 /// Keep all messages, at least until other resource limits are exceeded.
40 KeepAll,
41}
42
43/// The `RELIABILITY` DDS QoS policy.
44///
45/// This policy determines whether delivery between a publisher and a subscription will be retried
46/// until successful, or whether messages may be lost in a trade off for better performance.
47///
48/// # Compatibility
49/// | Publisher | Subscription | Compatible | Behavior |
50/// | -- | -- | -- | -- |
51/// | Reliable | Reliable | yes | Reliable |
52/// | Reliable | BestEffort | yes | Best effort |
53/// | BestEffort | Reliable | no | - |
54/// | BestEffort | BestEffort | yes | Best effort |
55///
56#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
57pub enum QoSReliabilityPolicy {
58 /// Use the default policy of the RMW layer.
59 SystemDefault = 0,
60 /// Guarantee delivery of messages.
61 Reliable = 1,
62 /// Send messages but do not guarantee delivery.
63 BestEffort = 2,
64}
65
66/// The `DURABILITY` DDS QoS policy.
67///
68/// If a subscription is created after some messages have already been published, it is possible
69/// for the subscription to receive a number of previously-published messages by using the
70/// "transient local" durability kind on both ends. For this, the publisher must still exist when
71/// the subscription is created.
72///
73/// # Compatibility
74/// | Publisher | Subscription | Compatible | Behavior |
75/// | -- | -- | -- | -- |
76/// | TransientLocal | TransientLocal | yes | Deliver old messages to new subscriptions |
77/// | TransientLocal | Volatile | yes | Deliver only new messages |
78/// | Volatile | TransientLocal | no | - |
79/// | Volatile | Volatile | yes | Deliver only new messages |
80///
81#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
82pub enum QoSDurabilityPolicy {
83 /// Use the default policy of the RMW layer.
84 SystemDefault = 0,
85 /// Re-deliver old messages.
86 /// - For publishers: Retain messages for later delivery.
87 /// - For subscriptions: Request delivery of old messages.
88 TransientLocal = 1,
89 /// Do not retain/request old messages.
90 Volatile = 2,
91}
92
93/// The `LIVELINESS` DDS QoS policy.
94///
95/// This policy describes a publisher's reporting policy for its alive status.
96/// For a subscription, these are its requirements for its topic's publishers.
97///
98/// # Compatibility
99/// | Publisher | Subscription | Compatible |
100/// | -- | -- | -- |
101/// | Automatic | Automatic | yes |
102/// | Automatic | ManualByTopic | no |
103/// | ManualByTopic | Automatic | yes |
104/// | ManualByTopic | ManualByTopic | yes |
105///
106#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
107pub enum QoSLivelinessPolicy {
108 /// Use the default policy of the RMW layer.
109 SystemDefault = 0,
110 /// The signal that establishes that a topic is alive comes from the ROS `rmw` layer.
111 Automatic = 1,
112 /// The signal that establishes that a topic is alive is sent explicitly. Only publishing a message
113 /// on the topic or an explicit signal from the application to assert liveliness on the topic
114 /// will mark the topic as being alive.
115 ManualByTopic = 3,
116}
117
118/// A duration that can take two special values: System default and infinite.
119#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
120pub enum QoSDuration {
121 /// This will use the RMW implementation's default value,
122 /// which may or may not be infinite.
123 SystemDefault,
124 /// This will act as an infinite duration.
125 Infinite,
126 /// A specific duration.
127 Custom(Duration),
128}
129
130/// A Quality of Service profile.
131///
132/// See [docs.ros.org][1] on Quality of Service settings in general.
133///
134/// In the general case, a topic can have multiple publishers and multiple subscriptions, each with
135/// an individual QoS profile. For each publisher-subscription pair, messages are only delivered if
136/// their QoS profiles are compatible.
137///
138/// # Example
139/// ```
140/// # use rclrs::{QoSProfile, QoSHistoryPolicy, QOS_PROFILE_SENSOR_DATA};
141/// let qos = QoSProfile {
142/// history: QoSHistoryPolicy::KeepLast { depth: 1 },
143/// ..QOS_PROFILE_SENSOR_DATA
144/// };
145/// ```
146///
147/// [1]: https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html
148#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
149pub struct QoSProfile {
150 /// The history policy.
151 pub history: QoSHistoryPolicy,
152 /// The reliability policy.
153 pub reliability: QoSReliabilityPolicy,
154 /// The durability policy.
155 pub durability: QoSDurabilityPolicy,
156 /// The period at which messages are expected to be sent/received.
157 ///
158 /// If this is `Infinite`, messages never miss a deadline expectation.
159 pub deadline: QoSDuration,
160 /// The age at which messages are considered expired and no longer valid.
161 ///
162 /// If this is `Infinite`, messages do not expire.
163 pub lifespan: QoSDuration,
164 /// The liveliness policy.
165 pub liveliness: QoSLivelinessPolicy,
166 /// The time within which the RMW publisher must show that it is alive.
167 ///
168 /// If this is `Infinite`, liveliness is not enforced.
169 pub liveliness_lease_duration: QoSDuration,
170 /// If true, any ROS specific namespacing conventions will be circumvented.
171 ///
172 /// In the case of DDS and topics, for example, this means the typical
173 /// ROS specific prefix of `rt` would not be applied as described [here][1].
174 ///
175 /// This might be useful when trying to directly connect a native DDS topic
176 /// with a ROS 2 topic.
177 ///
178 /// [1]: http://design.ros2.org/articles/topic_and_service_names.html#ros-specific-namespace-prefix
179 pub avoid_ros_namespace_conventions: bool,
180}
181
182impl From<QoSProfile> for rmw_qos_profile_t {
183 fn from(qos: QoSProfile) -> Self {
184 Self {
185 history: qos.history.into(),
186 depth: match qos.history {
187 QoSHistoryPolicy::SystemDefault { depth } => depth as usize,
188 QoSHistoryPolicy::KeepLast { depth } => depth as usize,
189 QoSHistoryPolicy::KeepAll => 0,
190 },
191 reliability: qos.reliability.into(),
192 durability: qos.durability.into(),
193 deadline: qos.deadline.into(),
194 lifespan: qos.lifespan.into(),
195 liveliness: qos.liveliness.into(),
196 liveliness_lease_duration: qos.liveliness_lease_duration.into(),
197 avoid_ros_namespace_conventions: qos.avoid_ros_namespace_conventions,
198 }
199 }
200}
201
202impl From<QoSHistoryPolicy> for rmw_qos_history_policy_t {
203 fn from(policy: QoSHistoryPolicy) -> Self {
204 match policy {
205 QoSHistoryPolicy::SystemDefault { .. } => {
206 rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT
207 }
208 QoSHistoryPolicy::KeepLast { .. } => {
209 rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_KEEP_LAST
210 }
211 QoSHistoryPolicy::KeepAll => rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_KEEP_ALL,
212 }
213 }
214}
215
216impl From<QoSReliabilityPolicy> for rmw_qos_reliability_policy_t {
217 fn from(policy: QoSReliabilityPolicy) -> Self {
218 match policy {
219 QoSReliabilityPolicy::SystemDefault => {
220 rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT
221 }
222 QoSReliabilityPolicy::Reliable => {
223 rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_RELIABLE
224 }
225 QoSReliabilityPolicy::BestEffort => {
226 rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
227 }
228 }
229 }
230}
231
232impl From<QoSDurabilityPolicy> for rmw_qos_durability_policy_t {
233 fn from(policy: QoSDurabilityPolicy) -> Self {
234 match policy {
235 QoSDurabilityPolicy::SystemDefault => {
236 rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT
237 }
238 QoSDurabilityPolicy::TransientLocal => {
239 rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
240 }
241 QoSDurabilityPolicy::Volatile => {
242 rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_VOLATILE
243 }
244 }
245 }
246}
247
248impl From<QoSLivelinessPolicy> for rmw_qos_liveliness_policy_t {
249 fn from(policy: QoSLivelinessPolicy) -> Self {
250 match policy {
251 QoSLivelinessPolicy::SystemDefault => {
252 rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT
253 }
254 QoSLivelinessPolicy::Automatic => {
255 rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
256 }
257 QoSLivelinessPolicy::ManualByTopic => {
258 rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
259 }
260 }
261 }
262}
263
264impl From<QoSDuration> for rmw_time_t {
265 fn from(duration: QoSDuration) -> Self {
266 match duration {
267 QoSDuration::Custom(dt) => {
268 let nonzero_dt = dt.max(Duration::from_nanos(1));
269 Self {
270 sec: nonzero_dt.as_secs(),
271 nsec: u64::from(nonzero_dt.subsec_nanos()),
272 }
273 }
274 // See RMW_DURATION_DEFAULT
275 QoSDuration::SystemDefault => Self { sec: 0, nsec: 0 },
276 // See RMW_DURATION_INFINITE
277 QoSDuration::Infinite => Self {
278 sec: 9223372036,
279 nsec: 854775807,
280 },
281 }
282 }
283}
284
285/// Equivalent to `rmw_qos_profile_sensor_data` from the [`rmw` package][1].
286///
287/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
288pub const QOS_PROFILE_SENSOR_DATA: QoSProfile = QoSProfile {
289 history: QoSHistoryPolicy::KeepLast { depth: 5 },
290 reliability: QoSReliabilityPolicy::BestEffort,
291 durability: QoSDurabilityPolicy::Volatile,
292 deadline: QoSDuration::SystemDefault,
293 lifespan: QoSDuration::SystemDefault,
294 liveliness: QoSLivelinessPolicy::SystemDefault,
295 liveliness_lease_duration: QoSDuration::SystemDefault,
296 avoid_ros_namespace_conventions: false,
297};
298
299/// Equivalent to `ClockQos` from the [`rclcpp` package][1].
300/// Same as sensor data but with a history depth of 1
301///
302/// [1]: https://github.com/ros2/rclcpp/blob/rolling/rclcpp/include/rclcpp/qos.hpp
303pub const QOS_PROFILE_CLOCK: QoSProfile = QoSProfile {
304 history: QoSHistoryPolicy::KeepLast { depth: 1 },
305 reliability: QoSReliabilityPolicy::BestEffort,
306 durability: QoSDurabilityPolicy::Volatile,
307 deadline: QoSDuration::SystemDefault,
308 lifespan: QoSDuration::SystemDefault,
309 liveliness: QoSLivelinessPolicy::SystemDefault,
310 liveliness_lease_duration: QoSDuration::SystemDefault,
311 avoid_ros_namespace_conventions: false,
312};
313
314/// Equivalent to `rmw_qos_profile_parameters` from the [`rmw` package][1].
315///
316/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
317pub const QOS_PROFILE_PARAMETERS: QoSProfile = QoSProfile {
318 history: QoSHistoryPolicy::KeepLast { depth: 1000 },
319 reliability: QoSReliabilityPolicy::Reliable,
320 durability: QoSDurabilityPolicy::Volatile,
321 deadline: QoSDuration::SystemDefault,
322 lifespan: QoSDuration::SystemDefault,
323 liveliness: QoSLivelinessPolicy::SystemDefault,
324 liveliness_lease_duration: QoSDuration::SystemDefault,
325 avoid_ros_namespace_conventions: false,
326};
327
328/// Equivalent to `rmw_qos_profile_default` from the [`rmw` package][1].
329///
330/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
331pub const QOS_PROFILE_DEFAULT: QoSProfile = QoSProfile {
332 history: QoSHistoryPolicy::KeepLast { depth: 10 },
333 reliability: QoSReliabilityPolicy::Reliable,
334 durability: QoSDurabilityPolicy::Volatile,
335 deadline: QoSDuration::SystemDefault,
336 lifespan: QoSDuration::SystemDefault,
337 liveliness: QoSLivelinessPolicy::SystemDefault,
338 liveliness_lease_duration: QoSDuration::SystemDefault,
339 avoid_ros_namespace_conventions: false,
340};
341
342/// Equivalent to `rmw_qos_profile_services_default` from the [`rmw` package][1].
343///
344/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
345pub const QOS_PROFILE_SERVICES_DEFAULT: QoSProfile = QoSProfile {
346 history: QoSHistoryPolicy::KeepLast { depth: 10 },
347 reliability: QoSReliabilityPolicy::Reliable,
348 durability: QoSDurabilityPolicy::Volatile,
349 deadline: QoSDuration::SystemDefault,
350 lifespan: QoSDuration::SystemDefault,
351 liveliness: QoSLivelinessPolicy::SystemDefault,
352 liveliness_lease_duration: QoSDuration::SystemDefault,
353 avoid_ros_namespace_conventions: false,
354};
355
356/// Equivalent to `rmw_qos_profile_parameter_events` from the [`rmw` package][1].
357///
358/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
359pub const QOS_PROFILE_PARAMETER_EVENTS: QoSProfile = QoSProfile {
360 history: QoSHistoryPolicy::KeepAll,
361 reliability: QoSReliabilityPolicy::Reliable,
362 durability: QoSDurabilityPolicy::Volatile,
363 deadline: QoSDuration::SystemDefault,
364 lifespan: QoSDuration::SystemDefault,
365 liveliness: QoSLivelinessPolicy::SystemDefault,
366 liveliness_lease_duration: QoSDuration::SystemDefault,
367 avoid_ros_namespace_conventions: false,
368};
369
370/// Equivalent to `rmw_qos_profile_system_default` from the [`rmw` package][1].
371///
372/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
373pub const QOS_PROFILE_SYSTEM_DEFAULT: QoSProfile = QoSProfile {
374 history: QoSHistoryPolicy::SystemDefault { depth: 0 },
375 reliability: QoSReliabilityPolicy::SystemDefault,
376 durability: QoSDurabilityPolicy::SystemDefault,
377 deadline: QoSDuration::SystemDefault,
378 lifespan: QoSDuration::SystemDefault,
379 liveliness: QoSLivelinessPolicy::SystemDefault,
380 liveliness_lease_duration: QoSDuration::SystemDefault,
381 avoid_ros_namespace_conventions: false,
382};