ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
qos.cpp
1 // Copyright 2019 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "rclcpp/qos.hpp"
16 
17 #include <string>
18 
19 #include "rmw/error_handling.h"
20 #include "rmw/types.h"
21 #include "rmw/qos_profiles.h"
22 
23 namespace rclcpp
24 {
25 
26 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind)
27 {
28  switch (policy_kind) {
29  case RMW_QOS_POLICY_DURABILITY:
30  return "DURABILITY_QOS_POLICY";
31  case RMW_QOS_POLICY_DEADLINE:
32  return "DEADLINE_QOS_POLICY";
33  case RMW_QOS_POLICY_LIVELINESS:
34  return "LIVELINESS_QOS_POLICY";
35  case RMW_QOS_POLICY_RELIABILITY:
36  return "RELIABILITY_QOS_POLICY";
37  case RMW_QOS_POLICY_HISTORY:
38  return "HISTORY_QOS_POLICY";
39  case RMW_QOS_POLICY_LIFESPAN:
40  return "LIFESPAN_QOS_POLICY";
41  default:
42  return "INVALID_QOS_POLICY";
43  }
44 }
45 
46 QoSInitialization::QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg)
47 : history_policy(history_policy_arg), depth(depth_arg)
48 {}
49 
51 QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos)
52 {
53  switch (rmw_qos.history) {
54  case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
55  return KeepAll();
56  case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
57  case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
58  case RMW_QOS_POLICY_HISTORY_UNKNOWN:
59  return KeepLast(rmw_qos.depth);
60  default:
61  throw std::invalid_argument(
62  "Invalid history policy enum value passed to QoSInitialization::from_rmw");
63  }
64 }
65 
66 KeepAll::KeepAll()
67 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 0)
68 {}
69 
70 KeepLast::KeepLast(size_t depth)
71 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth)
72 {}
73 
75  const QoSInitialization & qos_initialization,
76  const rmw_qos_profile_t & initial_profile)
77 : rmw_qos_profile_(initial_profile)
78 {
79  rmw_qos_profile_.history = qos_initialization.history_policy;
80  rmw_qos_profile_.depth = qos_initialization.depth;
81 }
82 
83 QoS::QoS(size_t history_depth)
84 : QoS(KeepLast(history_depth))
85 {}
86 
87 rmw_qos_profile_t &
89 {
90  return rmw_qos_profile_;
91 }
92 
93 const rmw_qos_profile_t &
95 {
96  return rmw_qos_profile_;
97 }
98 
99 QoS &
100 QoS::history(rmw_qos_history_policy_t history)
101 {
102  rmw_qos_profile_.history = history;
103  return *this;
104 }
105 
106 QoS &
107 QoS::history(HistoryPolicy history)
108 {
109  rmw_qos_profile_.history = static_cast<rmw_qos_history_policy_t>(history);
110  return *this;
111 }
112 
113 QoS &
114 QoS::keep_last(size_t depth)
115 {
116  rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
117  rmw_qos_profile_.depth = depth;
118  return *this;
119 }
120 
121 QoS &
123 {
124  rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
125  rmw_qos_profile_.depth = 0;
126  return *this;
127 }
128 
129 QoS &
130 QoS::reliability(rmw_qos_reliability_policy_t reliability)
131 {
132  rmw_qos_profile_.reliability = reliability;
133  return *this;
134 }
135 
136 QoS &
137 QoS::reliability(ReliabilityPolicy reliability)
138 {
139  rmw_qos_profile_.reliability = static_cast<rmw_qos_reliability_policy_t>(reliability);
140  return *this;
141 }
142 
143 QoS &
145 {
146  return this->reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
147 }
148 
149 QoS &
151 {
152  return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
153 }
154 
155 QoS &
156 QoS::durability(rmw_qos_durability_policy_t durability)
157 {
158  rmw_qos_profile_.durability = durability;
159  return *this;
160 }
161 
162 QoS &
163 QoS::durability(DurabilityPolicy durability)
164 {
165  rmw_qos_profile_.durability = static_cast<rmw_qos_durability_policy_t>(durability);
166  return *this;
167 }
168 
169 QoS &
171 {
172  return this->durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
173 }
174 
175 QoS &
177 {
178  return this->durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
179 }
180 
181 QoS &
182 QoS::deadline(rmw_time_t deadline)
183 {
184  rmw_qos_profile_.deadline = deadline;
185  return *this;
186 }
187 
188 QoS &
190 {
191  return this->deadline(deadline.to_rmw_time());
192 }
193 
194 QoS &
195 QoS::lifespan(rmw_time_t lifespan)
196 {
197  rmw_qos_profile_.lifespan = lifespan;
198  return *this;
199 }
200 
201 QoS &
203 {
204  return this->lifespan(lifespan.to_rmw_time());
205 }
206 
207 QoS &
208 QoS::liveliness(rmw_qos_liveliness_policy_t liveliness)
209 {
210  rmw_qos_profile_.liveliness = liveliness;
211  return *this;
212 }
213 
214 QoS &
215 QoS::liveliness(LivelinessPolicy liveliness)
216 {
217  rmw_qos_profile_.liveliness = static_cast<rmw_qos_liveliness_policy_t>(liveliness);
218  return *this;
219 }
220 
221 
222 QoS &
223 QoS::liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
224 {
225  rmw_qos_profile_.liveliness_lease_duration = liveliness_lease_duration;
226  return *this;
227 }
228 
229 QoS &
230 QoS::liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration)
231 {
232  return this->liveliness_lease_duration(liveliness_lease_duration.to_rmw_time());
233 }
234 
235 QoS &
236 QoS::avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
237 {
238  rmw_qos_profile_.avoid_ros_namespace_conventions = avoid_ros_namespace_conventions;
239  return *this;
240 }
241 
242 HistoryPolicy
244 {
245  return static_cast<HistoryPolicy>(rmw_qos_profile_.history);
246 }
247 
248 size_t
249 QoS::depth() const {return rmw_qos_profile_.depth;}
250 
251 ReliabilityPolicy
253 {
254  return static_cast<ReliabilityPolicy>(rmw_qos_profile_.reliability);
255 }
256 
257 DurabilityPolicy
259 {
260  return static_cast<DurabilityPolicy>(rmw_qos_profile_.durability);
261 }
262 
263 Duration
264 QoS::deadline() const {return Duration::from_rmw_time(rmw_qos_profile_.deadline);}
265 
266 Duration
267 QoS::lifespan() const {return Duration::from_rmw_time(rmw_qos_profile_.lifespan);}
268 
269 LivelinessPolicy
271 {
272  return static_cast<LivelinessPolicy>(rmw_qos_profile_.liveliness);
273 }
274 
275 Duration
277 {
278  return Duration::from_rmw_time(rmw_qos_profile_.liveliness_lease_duration);
279 }
280 
281 bool
283 {
284  return rmw_qos_profile_.avoid_ros_namespace_conventions;
285 }
286 
287 namespace
288 {
290 bool operator==(const rmw_time_t & left, const rmw_time_t & right)
291 {
292  return left.sec == right.sec && left.nsec == right.nsec;
293 }
294 } // unnamed namespace
295 
296 bool operator==(const QoS & left, const QoS & right)
297 {
298  const auto & pl = left.get_rmw_qos_profile();
299  const auto & pr = right.get_rmw_qos_profile();
300  return pl.history == pr.history &&
301  pl.depth == pr.depth &&
302  pl.reliability == pr.reliability &&
303  pl.durability == pr.durability &&
304  pl.deadline == pr.deadline &&
305  pl.lifespan == pr.lifespan &&
306  pl.liveliness == pr.liveliness &&
307  pl.liveliness_lease_duration == pr.liveliness_lease_duration &&
308  pl.avoid_ros_namespace_conventions == pr.avoid_ros_namespace_conventions;
309 }
310 
311 bool operator!=(const QoS & left, const QoS & right)
312 {
313  return !(left == right);
314 }
315 
316 QoSCheckCompatibleResult
317 qos_check_compatible(const QoS & publisher_qos, const QoS & subscription_qos)
318 {
319  rmw_qos_compatibility_type_t compatible;
320  const size_t reason_size = 2048u;
321  char reason_c_str[reason_size] = "";
322  rmw_ret_t ret = rmw_qos_profile_check_compatible(
323  publisher_qos.get_rmw_qos_profile(),
324  subscription_qos.get_rmw_qos_profile(),
325  &compatible,
326  reason_c_str,
327  reason_size);
328  if (RMW_RET_OK != ret) {
329  std::string error_str(rmw_get_error_string().str);
330  rmw_reset_error();
332  }
333 
335  result.reason = std::string(reason_c_str);
336 
337  switch (compatible) {
338  case RMW_QOS_COMPATIBILITY_OK:
339  result.compatibility = QoSCompatibility::Ok;
340  break;
341  case RMW_QOS_COMPATIBILITY_WARNING:
342  result.compatibility = QoSCompatibility::Warning;
343  break;
344  case RMW_QOS_COMPATIBILITY_ERROR:
345  result.compatibility = QoSCompatibility::Error;
346  break;
347  default:
349  "Unexpected compatibility value returned by rmw '" + std::to_string(compatible) +
350  "'"};
351  }
352  return result;
353 }
354 
355 ClockQoS::ClockQoS(const QoSInitialization & qos_initialization)
356 // Using `rmw_qos_profile_sensor_data` intentionally.
357 // It's best effort and `qos_initialization` is overriding the depth to 1.
358 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
359 {}
360 
361 SensorDataQoS::SensorDataQoS(const QoSInitialization & qos_initialization)
362 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
363 {}
364 
365 ParametersQoS::ParametersQoS(const QoSInitialization & qos_initialization)
366 : QoS(qos_initialization, rmw_qos_profile_parameters)
367 {}
368 
369 ServicesQoS::ServicesQoS(const QoSInitialization & qos_initialization)
370 : QoS(qos_initialization, rmw_qos_profile_services_default)
371 {}
372 
373 ParameterEventsQoS::ParameterEventsQoS(const QoSInitialization & qos_initialization)
374 : QoS(qos_initialization, rmw_qos_profile_parameter_events)
375 {}
376 
377 RosoutQoS::RosoutQoS(const QoSInitialization & rosout_initialization)
378 : QoS(rosout_initialization, rcl_qos_profile_rosout_default)
379 {}
380 
381 SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initialization)
382 : QoS(qos_initialization, rmw_qos_profile_system_default)
383 {}
384 
385 } // namespace rclcpp
rmw_time_t to_rmw_time() const
Convert Duration into rmw_time_t.
Definition: duration.cpp:244
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
QoS & best_effort()
Set the reliability setting to best effort.
Definition: qos.cpp:150
bool avoid_ros_namespace_conventions() const
Get the avoid ros namespace convention setting.
Definition: qos.cpp:282
QoS & reliable()
Set the reliability setting to reliable.
Definition: qos.cpp:144
QoS & keep_all()
Set the history to keep all.
Definition: qos.cpp:122
rclcpp::Duration deadline() const
Get the deadline duration setting.
Definition: qos.cpp:264
DurabilityPolicy durability() const
Get the durability policy.
Definition: qos.cpp:258
rclcpp::Duration lifespan() const
Get the lifespan duration setting.
Definition: qos.cpp:267
QoS & durability_volatile()
Set the durability setting to volatile.
Definition: qos.cpp:170
ReliabilityPolicy reliability() const
Get the reliability policy.
Definition: qos.cpp:252
LivelinessPolicy liveliness() const
Get the liveliness policy.
Definition: qos.cpp:270
HistoryPolicy history() const
Get the history qos policy.
Definition: qos.cpp:243
QoS(const QoSInitialization &qos_initialization, const rmw_qos_profile_t &initial_profile=rmw_qos_profile_default)
Create a QoS by specifying only the history policy and history depth.
Definition: qos.cpp:74
QoS & transient_local()
Set the durability setting to transient local.
Definition: qos.cpp:176
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
Definition: qos.cpp:88
size_t depth() const
Get the history depth.
Definition: qos.cpp:249
rclcpp::Duration liveliness_lease_duration() const
Get the liveliness lease duration setting.
Definition: qos.cpp:276
QoS & keep_last(size_t depth)
Set the history to keep last.
Definition: qos.cpp:114
QoS & liveliness_lease_duration(const rclcpp::Duration &liveliness_lease_duration)
Set the liveliness_lease_duration setting, rclcpp::Duration.
Definition: qos.cpp:230
Thrown if a QoS compatibility check fails.
Definition: exceptions.hpp:326
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC QoSCheckCompatibleResult qos_check_compatible(const QoS &publisher_qos, const QoS &subscription_qos)
Check if two QoS profiles are compatible.
Definition: qos.cpp:317
RCLCPP_PUBLIC bool operator==(const NetworkFlowEndpoint &left, const NetworkFlowEndpoint &right)
Check if two NetworkFlowEndpoint instances are equal.
RCLCPP_PUBLIC bool operator!=(const NetworkFlowEndpoint &left, const NetworkFlowEndpoint &right)
Check if two NetworkFlowEndpoint instances are not equal.
Use to initialize the QoS with the keep_all history setting.
Definition: qos.hpp:90
Use to initialize the QoS with the keep_last history setting and the given depth.
Definition: qos.hpp:96
Result type for checking QoS compatibility.
Definition: qos.hpp:289
QoSCompatibility compatibility
Compatibility result.
Definition: qos.hpp:291
std::string reason
Reason for a (possible) incompatibility.
Definition: qos.hpp:298
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:75
QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg)
Constructor which takes both a history policy and a depth (even if it would be unused).
Definition: qos.cpp:46
static QoSInitialization from_rmw(const rmw_qos_profile_t &rmw_qos)
Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.
Definition: qos.cpp:51