rclrs 0.7.0

A ROS 2 client library for developing robotics applications in Rust
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
use std::time::Duration;

use crate::{log_error, rcl_bindings::*};

/// The `HISTORY` DDS QoS policy.
///
/// A subscription internally maintains a queue of messages (called "samples" in DDS) that have not
/// been processed yet by the application, and likewise a publisher internally maintains a queue.
///
/// If the history policy is `KeepAll`, this queue is unbounded, and if it is `KeepLast`, it is
/// bounded and old values are discarded when the queue is overfull.
///
/// The `rmw` layer may not be able to handle very large queue depths, e.g. greater than
/// `i32::MAX`.
/// In this case, the functions taking the QoS profile as an argument will return an error.
///
/// # Compatibility
/// | Publisher | Subscription | Compatible |
/// | -- | -- | -- |
/// | KeepLast | KeepLast | yes |
/// | KeepLast | KeepAll | yes |
/// | KeepAll | KeepLast | yes |
/// | KeepAll | KeepAll | yes |
///
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub enum QoSHistoryPolicy {
    /// Use the default policy of the RMW layer.
    ///
    /// If the default policy is `KeepAll`, the depth will be ignored.
    SystemDefault {
        /// The length of the publisher/subscription queue.
        depth: u32,
    },
    /// Keep only the `depth` most recent messages.
    KeepLast {
        /// The length of the publisher/subscription queue.
        depth: u32,
    },
    /// Keep all messages, at least until other resource limits are exceeded.
    KeepAll,
}

/// The `RELIABILITY` DDS QoS policy.
///
/// This policy determines whether delivery between a publisher and a subscription will be retried
/// until successful, or whether messages may be lost in a trade off for better performance.
///
/// # Compatibility
/// | Publisher | Subscription | Compatible | Behavior |
/// | -- | -- | -- | -- |
/// | Reliable | Reliable | yes | Reliable |
/// | Reliable | BestEffort | yes | Best effort |
/// | BestEffort | Reliable | no | - |
/// | BestEffort | BestEffort | yes | Best effort |
///
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub enum QoSReliabilityPolicy {
    /// Use the default policy of the RMW layer.
    SystemDefault = 0,
    /// Guarantee delivery of messages.
    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.
///
/// If a subscription is created after some messages have already been published, it is possible
/// for the subscription to receive a number of previously-published messages by using the
/// "transient local" durability kind on both ends. For this, the publisher must still exist when
/// the subscription is created.
///
/// # Compatibility
/// | Publisher | Subscription | Compatible | Behavior |
/// | -- | -- | -- | -- |
/// | TransientLocal | TransientLocal | yes | Deliver old messages to new subscriptions |
/// | TransientLocal | Volatile | yes | Deliver only new messages |
/// | Volatile | TransientLocal | no | - |
/// | Volatile | Volatile | yes | Deliver only new messages |
///
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub enum QoSDurabilityPolicy {
    /// Use the default policy of the RMW layer.
    SystemDefault = 0,
    /// Re-deliver old messages.
    /// - For publishers: Retain messages for later delivery.
    /// - For subscriptions: Request delivery of old messages.
    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.
///
/// This policy describes a publisher's reporting policy for its alive status.
/// For a subscription, these are its requirements for its topic's publishers.
///
/// # Compatibility
/// | Publisher | Subscription | Compatible |
/// | -- | -- | -- |
/// | Automatic | Automatic | yes |
/// | Automatic | ManualByTopic | no |
/// | ManualByTopic | Automatic | yes |
/// | ManualByTopic | ManualByTopic | yes |
///
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub enum QoSLivelinessPolicy {
    /// Use the default policy of the RMW layer.
    SystemDefault = 0,
    /// The signal that establishes that a topic is alive comes from the ROS `rmw` layer.
    Automatic = 1,
    /// The signal that establishes that a topic is alive is sent explicitly. Only publishing a message
    /// 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.
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub enum QoSDuration {
    /// This will use the RMW implementation's default value,
    /// which may or may not be infinite.
    SystemDefault,
    /// This will act as an infinite duration.
    Infinite,
    /// A specific duration.
    Custom(Duration),
}

/// A Quality of Service profile.
///
/// See [docs.ros.org][1] on Quality of Service settings in general.
///
/// In the general case, a topic can have multiple publishers and multiple subscriptions, each with
/// an individual QoS profile. For each publisher-subscription pair, messages are only delivered if
/// their QoS profiles are compatible.
///
/// # Example
/// ```
/// # use rclrs::{QoSProfile, QoSHistoryPolicy, QOS_PROFILE_SENSOR_DATA};
/// let qos = QoSProfile {
///     history: QoSHistoryPolicy::KeepLast { depth: 1 },
///     ..QOS_PROFILE_SENSOR_DATA
/// };
/// ```
///
/// [1]: https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html
#[derive(Clone, Copy, Debug, Eq, Ord, PartialEq, PartialOrd)]
pub struct QoSProfile {
    /// The history policy.
    pub history: QoSHistoryPolicy,
    /// The reliability policy.
    pub reliability: QoSReliabilityPolicy,
    /// The durability policy.
    pub durability: QoSDurabilityPolicy,
    /// The period at which messages are expected to be sent/received.
    ///
    /// If this is `Infinite`, messages never miss a deadline expectation.
    pub deadline: QoSDuration,
    /// The age at which messages are considered expired and no longer valid.
    ///
    /// If this is `Infinite`, messages do not expire.
    pub lifespan: QoSDuration,
    /// The liveliness policy.
    pub liveliness: QoSLivelinessPolicy,
    /// The time within which the RMW publisher must show that it is alive.
    ///
    /// If this is `Infinite`, liveliness is not enforced.
    pub liveliness_lease: QoSDuration,
    /// If true, any ROS specific namespacing conventions will be circumvented.
    ///
    /// In the case of DDS and topics, for example, this means the typical
    /// ROS specific prefix of `rt` would not be applied as described [here][1].
    ///
    /// This might be useful when trying to directly connect a native DDS topic
    /// with a ROS 2 topic.
    ///
    /// [1]: http://design.ros2.org/articles/topic_and_service_names.html#ros-specific-namespace-prefix
    pub avoid_ros_namespace_conventions: bool,
}

/// Sets the `QoSProfile` to the RCL default.
impl Default for QoSProfile {
    fn default() -> Self {
        QOS_PROFILE_DEFAULT
    }
}

impl From<QoSProfile> for rmw_qos_profile_t {
    fn from(qos: QoSProfile) -> Self {
        Self {
            history: qos.history.into(),
            depth: match qos.history {
                QoSHistoryPolicy::SystemDefault { depth } => depth as usize,
                QoSHistoryPolicy::KeepLast { depth } => depth as usize,
                QoSHistoryPolicy::KeepAll => 0,
            },
            reliability: qos.reliability.into(),
            durability: qos.durability.into(),
            deadline: qos.deadline.into(),
            lifespan: qos.lifespan.into(),
            liveliness: qos.liveliness.into(),
            liveliness_lease_duration: qos.liveliness_lease.into(),
            avoid_ros_namespace_conventions: qos.avoid_ros_namespace_conventions,
        }
    }
}

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 {
        self.history = QoSHistoryPolicy::KeepLast { depth };
        self
    }

    /// Sets the QoS profile history to [QoSHistoryPolicy::KeepAll].
    pub fn keep_all(mut self) -> Self {
        self.history = QoSHistoryPolicy::KeepAll;
        self
    }

    /// Sets the QoS profile reliability to [QoSReliabilityPolicy::Reliable].
    pub fn reliable(mut self) -> Self {
        self.reliability = QoSReliabilityPolicy::Reliable;
        self
    }

    /// Sets the QoS profile reliability to [QoSReliabilityPolicy::BestEffort].
    pub fn best_effort(mut self) -> Self {
        self.reliability = QoSReliabilityPolicy::BestEffort;
        self
    }

    /// Sets the QoS profile durability to [QoSDurabilityPolicy::Volatile].
    pub fn volatile(mut self) -> Self {
        self.durability = QoSDurabilityPolicy::Volatile;
        self
    }

    /// Sets the QoS profile durability to [QoSDurabilityPolicy::TransientLocal].
    pub fn transient_local(mut self) -> Self {
        self.durability = QoSDurabilityPolicy::TransientLocal;
        self
    }

    /// Sets the QoS profile deadline to the specified `Duration`.
    pub fn deadline_duration(mut self, deadline: Duration) -> Self {
        self.deadline = QoSDuration::Custom(deadline);
        self
    }

    /// Sets the QoS profile liveliness lease duration to the specified `Duration`.
    pub fn liveliness_lease_duration(mut self, lease_duration: Duration) -> Self {
        self.liveliness_lease = QoSDuration::Custom(lease_duration);
        self
    }

    /// Sets the QoS profile lifespan to the specified `Duration`.
    pub fn lifespan_duration(mut self, lifespan: Duration) -> Self {
        self.lifespan = QoSDuration::Custom(lifespan);
        self
    }

    /// Get the default QoS profile for ordinary topics.
    pub fn topics_default() -> Self {
        QOS_PROFILE_DEFAULT
    }

    /// Get the default QoS profile for topics that transmit sensor data.
    pub fn sensor_data_default() -> Self {
        QOS_PROFILE_SENSOR_DATA
    }

    /// Get the default QoS profile for services.
    pub fn services_default() -> Self {
        QOS_PROFILE_SERVICES_DEFAULT
    }

    /// Get the default QoS profile for parameter services.
    pub fn parameter_services_default() -> Self {
        QOS_PROFILE_PARAMETERS
    }

    /// Get the default QoS profile for parameter event topics.
    pub fn parameter_events_default() -> Self {
        QOS_PROFILE_PARAMETER_EVENTS
    }

    /// Get the system-defined default quality of service profile. Topics and
    /// services created with this default do not use the recommended ROS
    /// defaults; they will instead use the default as defined by the underlying
    /// RMW implementation (rmw_fastrtps, rmw_connextdds, etc). These defaults
    /// may not always be appropriate for every use-case, and may be different
    /// depending on which RMW implementation you are using, so use caution!
    pub fn system_default() -> Self {
        QOS_PROFILE_SYSTEM_DEFAULT
    }

    /// Get the default QoS profile for action status topics.
    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.
    #[cfg(not(ros_distro = "humble"))]
    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<QoSHistoryPolicy> for rmw_qos_history_policy_t {
    fn from(policy: QoSHistoryPolicy) -> Self {
        match policy {
            QoSHistoryPolicy::SystemDefault { .. } => {
                rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT
            }
            QoSHistoryPolicy::KeepLast { .. } => {
                rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_KEEP_LAST
            }
            QoSHistoryPolicy::KeepAll => rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_KEEP_ALL,
        }
    }
}

impl From<QoSReliabilityPolicy> for rmw_qos_reliability_policy_t {
    fn from(policy: QoSReliabilityPolicy) -> Self {
        match policy {
            QoSReliabilityPolicy::SystemDefault => {
                rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT
            }
            QoSReliabilityPolicy::Reliable => {
                rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_RELIABLE
            }
            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
            }
        }
    }
}

impl From<QoSDurabilityPolicy> for rmw_qos_durability_policy_t {
    fn from(policy: QoSDurabilityPolicy) -> Self {
        match policy {
            QoSDurabilityPolicy::SystemDefault => {
                rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT
            }
            QoSDurabilityPolicy::TransientLocal => {
                rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
            }
            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
            }
        }
    }
}

impl From<QoSLivelinessPolicy> for rmw_qos_liveliness_policy_t {
    fn from(policy: QoSLivelinessPolicy) -> Self {
        match policy {
            QoSLivelinessPolicy::SystemDefault => {
                rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT
            }
            QoSLivelinessPolicy::Automatic => {
                rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
            }
            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
            }
        }
    }
}

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
            }
            #[cfg(not(ros_distro = "humble"))]
            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
            }
        }
    }
}

impl From<QoSDuration> for rmw_time_t {
    fn from(duration: QoSDuration) -> Self {
        match duration {
            QoSDuration::Custom(dt) => {
                let nonzero_dt = dt.max(Duration::from_nanos(1));
                Self {
                    sec: nonzero_dt.as_secs(),
                    nsec: u64::from(nonzero_dt.subsec_nanos()),
                }
            }
            // See RMW_DURATION_DEFAULT
            QoSDuration::SystemDefault => Self { sec: 0, nsec: 0 },
            // See RMW_DURATION_INFINITE
            QoSDuration::Infinite => Self {
                sec: 9223372036,
                nsec: 854775807,
            },
        }
    }
}

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
pub const QOS_PROFILE_SENSOR_DATA: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 5 },
    reliability: QoSReliabilityPolicy::BestEffort,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `ClockQos` from the [`rclcpp` package][1].
/// Same as sensor data but with a history depth of 1
///
/// [1]: https://github.com/ros2/rclcpp/blob/rolling/rclcpp/include/rclcpp/qos.hpp
pub const QOS_PROFILE_CLOCK: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 1 },
    reliability: QoSReliabilityPolicy::BestEffort,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rmw_qos_profile_parameters` from the [`rmw` package][1].
///
/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
pub const QOS_PROFILE_PARAMETERS: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 1000 },
    reliability: QoSReliabilityPolicy::Reliable,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rmw_qos_profile_default` from the [`rmw` package][1].
///
/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
pub const QOS_PROFILE_DEFAULT: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 10 },
    reliability: QoSReliabilityPolicy::Reliable,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rmw_qos_profile_services_default` from the [`rmw` package][1].
///
/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
pub const QOS_PROFILE_SERVICES_DEFAULT: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 10 },
    reliability: QoSReliabilityPolicy::Reliable,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rmw_qos_profile_parameter_events` from the [`rmw` package][1].
///
/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
pub const QOS_PROFILE_PARAMETER_EVENTS: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepAll,
    reliability: QoSReliabilityPolicy::Reliable,
    durability: QoSDurabilityPolicy::Volatile,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rmw_qos_profile_system_default` from the [`rmw` package][1].
///
/// [1]: https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
pub const QOS_PROFILE_SYSTEM_DEFAULT: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::SystemDefault { depth: 0 },
    reliability: QoSReliabilityPolicy::SystemDefault,
    durability: QoSDurabilityPolicy::SystemDefault,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};

/// Equivalent to `rcl_action_qos_profile_status_default` from the [`rcl_action` package][1].
///
/// [1]: https://github.com/ros2/rcl/blob/rolling/rcl_action/include/rcl_action/default_qos.h
pub const QOS_PROFILE_ACTION_STATUS_DEFAULT: QoSProfile = QoSProfile {
    history: QoSHistoryPolicy::KeepLast { depth: 1 },
    reliability: QoSReliabilityPolicy::Reliable,
    durability: QoSDurabilityPolicy::TransientLocal,
    deadline: QoSDuration::SystemDefault,
    lifespan: QoSDuration::SystemDefault,
    liveliness: QoSLivelinessPolicy::SystemDefault,
    liveliness_lease: QoSDuration::SystemDefault,
    avoid_ros_namespace_conventions: false,
};