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
//! QoS of ROS2.

#[cfg(feature = "galactic")]
pub mod galactic;

#[cfg(feature = "humble")]
pub mod humble;

#[cfg(feature = "iron")]
pub mod iron;

pub mod policy;

// pub mod policy;

use crate::rcl;
use num_traits::{FromPrimitive, ToPrimitive};
use policy::*;
use std::time::Duration;

/// Represent QoS profile.
#[derive(Debug, Clone)]
pub struct Profile {
    /// Keep last: only store up to N samples, configurable via the queue depth option.
    /// Keep all: store all samples, subject to the configured resource limits of the underlying middleware.
    pub history: HistoryPolicy,

    /// Size of the message queue.
    pub depth: usize,

    /// Reliabiilty QoS policy setting.
    pub reliability: ReliabilityPolicy,

    /// Durability QoS policy setting.
    pub durability: DurabilityPolicy,

    /// The period at which messages are expected to be sent/received.
    /// RMW_DURATION_UNSPEFICIED will use the RMW implementation's default value,
    /// which may or may not be infinite.
    /// RMW_DURATION_INFINITE explicitly states that messages never miss a deadline expectation.
    pub deadline: Duration,

    /// The age at which messages are considered expired and no longer valid.
    /// RMW_DURATION_UNSPEFICIED will use the RMW implementation's default value,
    /// which may or may not be infinite.
    /// RMW_DURATION_INFINITE explicitly states that messages do not expire.
    pub lifespan: Duration,

    /// Liveliness QoS policy setting.
    pub liveliness: LivelinessPolicy,

    /// The time within which the RMW node or publisher must show that it is alive.
    /// RMW_DURATION_UNSPEFICIED will use the RMW implementation's default value,
    /// which may or may not be infinite.
    /// RMW_DURATION_INFINITE explicitly states that liveliness is not enforced.
    pub liveliness_lease_duration: Duration,

    /// 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:
    /// <http://design.ros2.org/articles/topic_and_service_names.html#ros-specific-namespace-prefix>.
    /// This might be useful when trying to directly connect a native DDS topic
    /// with a ROS 2 topic.
    pub avoid_ros_namespace_conventions: bool,
}

impl Default for Profile {
    /// Default QoS class
    /// - History: Keep last,
    /// - Depth: 10,
    /// - Reliability: Reliable,
    /// - Durability: Volatile,
    /// - Deadline: Default,
    /// - Lifespan: Default,
    /// - Liveliness: System default,
    /// - Liveliness lease duration: Default,
    /// - Avoid ros namespace conventions: false
    fn default() -> Self {
        Self {
            history: HistoryPolicy::KeepLast,
            depth: 10,
            reliability: ReliabilityPolicy::Reliable,
            durability: DurabilityPolicy::Volatile,
            ..Self::common()
        }
    }
}

impl Profile {
    const fn common() -> Self {
        Self {
            history: HistoryPolicy::SystemDefault,
            depth: rcl::RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT as usize,
            reliability: ReliabilityPolicy::SystemDefault,
            durability: DurabilityPolicy::SystemDefault,
            deadline: Duration::ZERO,
            lifespan: Duration::ZERO,
            liveliness: LivelinessPolicy::SystemDefault,
            liveliness_lease_duration: Duration::ZERO,
            avoid_ros_namespace_conventions: false,
        }
    }

    /// Services QoS class
    /// - History: Keep last,
    /// - Depth: 10,
    /// - Reliability: Reliable,
    /// - Durability: Volatile,
    /// - Deadline: Default,
    /// - Lifespan: Default,
    /// - Liveliness: System default,
    /// - Liveliness lease duration: Default,
    /// - Avoid ros namespace conventions: false
    pub fn services_default() -> Self {
        Self {
            history: HistoryPolicy::KeepLast,
            depth: 10,
            reliability: ReliabilityPolicy::Reliable,
            durability: DurabilityPolicy::Volatile,
            ..Self::common()
        }
    }

    /// Sensor Data QoS class
    /// - History: Keep last,
    /// - Depth: 5,
    /// - Reliability: Best effort,
    /// - Durability: Volatile,
    /// - Deadline: Default,
    /// - Lifespan: Default,
    /// - Liveliness: System default,
    /// - Liveliness lease duration: Default,
    /// - avoid ros namespace conventions: false
    pub const fn sensor_data() -> Self {
        Self {
            history: HistoryPolicy::KeepLast,
            depth: 5,
            reliability: ReliabilityPolicy::BestEffort,
            durability: DurabilityPolicy::Volatile,
            ..Self::common()
        }
    }

    /// Parameters QoS class
    /// - History: Keep last,
    /// - Depth: 1000,
    /// - Reliability: Reliable,
    /// - Durability: Volatile,
    /// - Deadline: Default,
    /// - Lifespan: Default,
    /// - Liveliness: System default,
    /// - Liveliness lease duration: Default,
    /// - Avoid ros namespace conventions: false
    pub const fn parameters() -> Self {
        Self {
            history: HistoryPolicy::KeepLast,
            depth: 1000,
            reliability: ReliabilityPolicy::Reliable,
            durability: DurabilityPolicy::Volatile,
            ..Self::common()
        }
    }
}

impl From<&rcl::rmw_qos_profile_t> for Profile {
    fn from(qos: &rcl::rmw_qos_profile_t) -> Self {
        Self {
            history: FromPrimitive::from_u32(qos.history).unwrap_or(HistoryPolicy::Unknown),
            depth: qos.depth as usize,
            reliability: FromPrimitive::from_u32(qos.reliability)
                .unwrap_or(ReliabilityPolicy::Unknown),
            durability: FromPrimitive::from_u32(qos.durability)
                .unwrap_or(DurabilityPolicy::Unknown),
            liveliness: FromPrimitive::from_u32(qos.liveliness)
                .unwrap_or(LivelinessPolicy::Unknown),
            deadline: qos.deadline.into(),
            lifespan: qos.lifespan.into(),
            liveliness_lease_duration: qos.liveliness_lease_duration.into(),
            avoid_ros_namespace_conventions: qos.avoid_ros_namespace_conventions,
        }
    }
}

impl From<&Profile> for rcl::rmw_qos_profile_t {
    #[cfg(feature = "galactic")]
    fn from(qos: &Profile) -> Self {
        rcl::rmw_qos_profile_t {
            history: ToPrimitive::to_u32(&qos.history)
                .unwrap_or(rcl::rmw_qos_history_policy_t_RMW_QOS_POLICY_HISTORY_UNKNOWN),
            depth: qos.depth as u64,
            reliability: ToPrimitive::to_u32(&qos.reliability)
                .unwrap_or(rcl::rmw_qos_reliability_policy_t_RMW_QOS_POLICY_RELIABILITY_UNKNOWN),
            durability: ToPrimitive::to_u32(&qos.durability)
                .unwrap_or(rcl::rmw_qos_durability_policy_t_RMW_QOS_POLICY_DURABILITY_UNKNOWN),
            liveliness: ToPrimitive::to_u32(&qos.liveliness)
                .unwrap_or(rcl::rmw_qos_liveliness_policy_t_RMW_QOS_POLICY_LIVELINESS_UNKNOWN),
            deadline: qos.deadline.into(),
            lifespan: qos.lifespan.into(),
            liveliness_lease_duration: qos.liveliness_lease_duration.into(),
            avoid_ros_namespace_conventions: qos.avoid_ros_namespace_conventions,
        }
    }

    #[cfg(any(feature = "humble", feature = "iron"))]
    fn from(qos: &Profile) -> Self {
        rcl::rmw_qos_profile_t {
            history: ToPrimitive::to_u32(&qos.history)
                .unwrap_or(rcl::rmw_qos_history_policy_e_RMW_QOS_POLICY_HISTORY_UNKNOWN),
            depth: qos.depth as _,
            reliability: ToPrimitive::to_u32(&qos.reliability)
                .unwrap_or(rcl::rmw_qos_reliability_policy_e_RMW_QOS_POLICY_RELIABILITY_UNKNOWN),
            durability: ToPrimitive::to_u32(&qos.durability)
                .unwrap_or(rcl::rmw_qos_durability_policy_e_RMW_QOS_POLICY_DURABILITY_UNKNOWN),
            liveliness: ToPrimitive::to_u32(&qos.liveliness)
                .unwrap_or(rcl::rmw_qos_liveliness_policy_e_RMW_QOS_POLICY_LIVELINESS_UNKNOWN),
            deadline: qos.deadline.into(),
            lifespan: qos.lifespan.into(),
            liveliness_lease_duration: qos.liveliness_lease_duration.into(),
            avoid_ros_namespace_conventions: qos.avoid_ros_namespace_conventions,
        }
    }
}