ROS 2 rclcpp + rcl - jazzy  jazzy
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 "rclcpp/logging.hpp"
20 
21 #include "rmw/error_handling.h"
22 #include "rmw/types.h"
23 #include "rmw/qos_profiles.h"
24 
25 namespace rclcpp
26 {
27 
28 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind)
29 {
30  switch (policy_kind) {
31  case RMW_QOS_POLICY_DURABILITY:
32  return "DURABILITY_QOS_POLICY";
33  case RMW_QOS_POLICY_DEADLINE:
34  return "DEADLINE_QOS_POLICY";
35  case RMW_QOS_POLICY_LIVELINESS:
36  return "LIVELINESS_QOS_POLICY";
37  case RMW_QOS_POLICY_RELIABILITY:
38  return "RELIABILITY_QOS_POLICY";
39  case RMW_QOS_POLICY_HISTORY:
40  return "HISTORY_QOS_POLICY";
41  case RMW_QOS_POLICY_LIFESPAN:
42  return "LIFESPAN_QOS_POLICY";
43  default:
44  return "INVALID_QOS_POLICY";
45  }
46 }
47 
49  rmw_qos_history_policy_t history_policy_arg, size_t depth_arg,
50  bool print_depth_warning)
51 : history_policy(history_policy_arg), depth(depth_arg)
52 {
53  if (history_policy == RMW_QOS_POLICY_HISTORY_KEEP_LAST && depth == 0 && print_depth_warning) {
54  RCLCPP_WARN_ONCE(
56  "rclcpp"),
57  "A zero depth with KEEP_LAST doesn't make sense; no data could be stored. "
58  "This will be interpreted as SYSTEM_DEFAULT");
59  }
60 }
61 
63 QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos)
64 {
65  switch (rmw_qos.history) {
66  case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
67  return KeepAll();
68  case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
69  return KeepLast(rmw_qos.depth, false);
70  case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
71  case RMW_QOS_POLICY_HISTORY_UNKNOWN:
72  return KeepLast(rmw_qos.depth);
73  default:
74  throw std::invalid_argument(
75  "Invalid history policy enum value passed to QoSInitialization::from_rmw");
76  }
77 }
78 
79 KeepAll::KeepAll()
80 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 0)
81 {}
82 
83 KeepLast::KeepLast(size_t depth, bool print_depth_warning)
84 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth, print_depth_warning)
85 {
86 }
87 
89  const QoSInitialization & qos_initialization,
90  const rmw_qos_profile_t & initial_profile)
91 : rmw_qos_profile_(initial_profile)
92 {
93  rmw_qos_profile_.history = qos_initialization.history_policy;
94  rmw_qos_profile_.depth = qos_initialization.depth;
95 }
96 
97 QoS::QoS(size_t history_depth)
98 : QoS(KeepLast(history_depth))
99 {}
100 
101 rmw_qos_profile_t &
103 {
104  return rmw_qos_profile_;
105 }
106 
107 const rmw_qos_profile_t &
109 {
110  return rmw_qos_profile_;
111 }
112 
113 QoS &
114 QoS::history(rmw_qos_history_policy_t history)
115 {
116  rmw_qos_profile_.history = history;
117  return *this;
118 }
119 
120 QoS &
121 QoS::history(HistoryPolicy history)
122 {
123  rmw_qos_profile_.history = static_cast<rmw_qos_history_policy_t>(history);
124  return *this;
125 }
126 
127 QoS &
128 QoS::keep_last(size_t depth)
129 {
130  if (depth == 0) {
131  RCLCPP_WARN_ONCE(
133  "rclcpp"),
134  "A zero depth with KEEP_LAST doesn't make sense; no data could be stored."
135  "This will be interpreted as SYSTEM_DEFAULT");
136  }
137 
138  rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
139  rmw_qos_profile_.depth = depth;
140  return *this;
141 }
142 
143 QoS &
145 {
146  rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
147  rmw_qos_profile_.depth = 0;
148  return *this;
149 }
150 
151 QoS &
152 QoS::reliability(rmw_qos_reliability_policy_t reliability)
153 {
154  rmw_qos_profile_.reliability = reliability;
155  return *this;
156 }
157 
158 QoS &
159 QoS::reliability(ReliabilityPolicy reliability)
160 {
161  rmw_qos_profile_.reliability = static_cast<rmw_qos_reliability_policy_t>(reliability);
162  return *this;
163 }
164 
165 QoS &
167 {
168  return this->reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
169 }
170 
171 QoS &
173 {
174  return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
175 }
176 
177 QoS &
179 {
180  return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE);
181 }
182 
183 QoS &
184 QoS::durability(rmw_qos_durability_policy_t durability)
185 {
186  rmw_qos_profile_.durability = durability;
187  return *this;
188 }
189 
190 QoS &
191 QoS::durability(DurabilityPolicy durability)
192 {
193  rmw_qos_profile_.durability = static_cast<rmw_qos_durability_policy_t>(durability);
194  return *this;
195 }
196 
197 QoS &
199 {
200  return this->durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
201 }
202 
203 QoS &
205 {
206  return this->durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
207 }
208 
209 QoS &
211 {
212  return this->durability(RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE);
213 }
214 
215 QoS &
216 QoS::deadline(rmw_time_t deadline)
217 {
218  rmw_qos_profile_.deadline = deadline;
219  return *this;
220 }
221 
222 QoS &
224 {
225  return this->deadline(deadline.to_rmw_time());
226 }
227 
228 QoS &
229 QoS::lifespan(rmw_time_t lifespan)
230 {
231  rmw_qos_profile_.lifespan = lifespan;
232  return *this;
233 }
234 
235 QoS &
237 {
238  return this->lifespan(lifespan.to_rmw_time());
239 }
240 
241 QoS &
242 QoS::liveliness(rmw_qos_liveliness_policy_t liveliness)
243 {
244  rmw_qos_profile_.liveliness = liveliness;
245  return *this;
246 }
247 
248 QoS &
249 QoS::liveliness(LivelinessPolicy liveliness)
250 {
251  rmw_qos_profile_.liveliness = static_cast<rmw_qos_liveliness_policy_t>(liveliness);
252  return *this;
253 }
254 
255 
256 QoS &
257 QoS::liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
258 {
259  rmw_qos_profile_.liveliness_lease_duration = liveliness_lease_duration;
260  return *this;
261 }
262 
263 QoS &
264 QoS::liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration)
265 {
266  return this->liveliness_lease_duration(liveliness_lease_duration.to_rmw_time());
267 }
268 
269 QoS &
270 QoS::avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
271 {
272  rmw_qos_profile_.avoid_ros_namespace_conventions = avoid_ros_namespace_conventions;
273  return *this;
274 }
275 
276 HistoryPolicy
278 {
279  return static_cast<HistoryPolicy>(rmw_qos_profile_.history);
280 }
281 
282 size_t
283 QoS::depth() const {return rmw_qos_profile_.depth;}
284 
285 ReliabilityPolicy
287 {
288  return static_cast<ReliabilityPolicy>(rmw_qos_profile_.reliability);
289 }
290 
291 DurabilityPolicy
293 {
294  return static_cast<DurabilityPolicy>(rmw_qos_profile_.durability);
295 }
296 
297 Duration
298 QoS::deadline() const {return Duration::from_rmw_time(rmw_qos_profile_.deadline);}
299 
300 Duration
301 QoS::lifespan() const {return Duration::from_rmw_time(rmw_qos_profile_.lifespan);}
302 
303 LivelinessPolicy
305 {
306  return static_cast<LivelinessPolicy>(rmw_qos_profile_.liveliness);
307 }
308 
309 Duration
311 {
312  return Duration::from_rmw_time(rmw_qos_profile_.liveliness_lease_duration);
313 }
314 
315 bool
317 {
318  return rmw_qos_profile_.avoid_ros_namespace_conventions;
319 }
320 
321 namespace
322 {
324 bool operator==(const rmw_time_t & left, const rmw_time_t & right)
325 {
326  return left.sec == right.sec && left.nsec == right.nsec;
327 }
328 } // unnamed namespace
329 
330 bool operator==(const QoS & left, const QoS & right)
331 {
332  const auto & pl = left.get_rmw_qos_profile();
333  const auto & pr = right.get_rmw_qos_profile();
334  return pl.history == pr.history &&
335  pl.depth == pr.depth &&
336  pl.reliability == pr.reliability &&
337  pl.durability == pr.durability &&
338  pl.deadline == pr.deadline &&
339  pl.lifespan == pr.lifespan &&
340  pl.liveliness == pr.liveliness &&
341  pl.liveliness_lease_duration == pr.liveliness_lease_duration &&
342  pl.avoid_ros_namespace_conventions == pr.avoid_ros_namespace_conventions;
343 }
344 
345 bool operator!=(const QoS & left, const QoS & right)
346 {
347  return !(left == right);
348 }
349 
350 QoSCheckCompatibleResult
351 qos_check_compatible(const QoS & publisher_qos, const QoS & subscription_qos)
352 {
353  rmw_qos_compatibility_type_t compatible;
354  const size_t reason_size = 2048u;
355  char reason_c_str[reason_size] = "";
356  rmw_ret_t ret = rmw_qos_profile_check_compatible(
357  publisher_qos.get_rmw_qos_profile(),
358  subscription_qos.get_rmw_qos_profile(),
359  &compatible,
360  reason_c_str,
361  reason_size);
362  if (RMW_RET_OK != ret) {
363  std::string error_str(rmw_get_error_string().str);
364  rmw_reset_error();
366  }
367 
369  result.reason = std::string(reason_c_str);
370 
371  switch (compatible) {
372  case RMW_QOS_COMPATIBILITY_OK:
373  result.compatibility = QoSCompatibility::Ok;
374  break;
375  case RMW_QOS_COMPATIBILITY_WARNING:
376  result.compatibility = QoSCompatibility::Warning;
377  break;
378  case RMW_QOS_COMPATIBILITY_ERROR:
379  result.compatibility = QoSCompatibility::Error;
380  break;
381  default:
383  "Unexpected compatibility value returned by rmw '" + std::to_string(compatible) +
384  "'"};
385  }
386  return result;
387 }
388 
389 ClockQoS::ClockQoS(const QoSInitialization & qos_initialization)
390 // Using `rmw_qos_profile_sensor_data` intentionally.
391 // It's best effort and `qos_initialization` is overriding the depth to 1.
392 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
393 {}
394 
395 SensorDataQoS::SensorDataQoS(const QoSInitialization & qos_initialization)
396 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
397 {}
398 
399 ParametersQoS::ParametersQoS(const QoSInitialization & qos_initialization)
400 : QoS(qos_initialization, rmw_qos_profile_parameters)
401 {}
402 
403 ServicesQoS::ServicesQoS(const QoSInitialization & qos_initialization)
404 : QoS(qos_initialization, rmw_qos_profile_services_default)
405 {}
406 
407 ParameterEventsQoS::ParameterEventsQoS(const QoSInitialization & qos_initialization)
408 : QoS(qos_initialization, rmw_qos_profile_parameter_events)
409 {}
410 
411 RosoutQoS::RosoutQoS(const QoSInitialization & rosout_initialization)
412 : QoS(rosout_initialization, rcl_qos_profile_rosout_default)
413 {}
414 
415 SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initialization)
416 : QoS(qos_initialization, rmw_qos_profile_system_default)
417 {}
418 
419 BestAvailableQoS::BestAvailableQoS(const QoSInitialization & qos_initialization)
420 : QoS(qos_initialization, rmw_qos_profile_best_available)
421 {}
422 
423 } // namespace rclcpp
rmw_time_t to_rmw_time() const
Convert Duration into rmw_time_t.
Definition: duration.cpp:267
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
QoS & durability_best_available()
Set the durability setting to best available.
Definition: qos.cpp:210
QoS & best_effort()
Set the reliability setting to best effort.
Definition: qos.cpp:172
bool avoid_ros_namespace_conventions() const
Get the avoid ros namespace convention setting.
Definition: qos.cpp:316
QoS & reliable()
Set the reliability setting to reliable.
Definition: qos.cpp:166
QoS & keep_all()
Set the history to keep all.
Definition: qos.cpp:144
rclcpp::Duration deadline() const
Get the deadline duration setting.
Definition: qos.cpp:298
DurabilityPolicy durability() const
Get the durability policy.
Definition: qos.cpp:292
rclcpp::Duration lifespan() const
Get the lifespan duration setting.
Definition: qos.cpp:301
QoS & durability_volatile()
Set the durability setting to volatile.
Definition: qos.cpp:198
ReliabilityPolicy reliability() const
Get the reliability policy.
Definition: qos.cpp:286
LivelinessPolicy liveliness() const
Get the liveliness policy.
Definition: qos.cpp:304
HistoryPolicy history() const
Get the history qos policy.
Definition: qos.cpp:277
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:88
QoS & reliability_best_available()
Set the reliability setting to best available.
Definition: qos.cpp:178
QoS & transient_local()
Set the durability setting to transient local.
Definition: qos.cpp:204
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
Definition: qos.cpp:102
size_t depth() const
Get the history depth.
Definition: qos.cpp:283
rclcpp::Duration liveliness_lease_duration() const
Get the liveliness lease duration setting.
Definition: qos.cpp:310
QoS & keep_last(size_t depth)
Set the history to keep last.
Definition: qos.cpp:128
Thrown if a QoS compatibility check fails.
Definition: exceptions.hpp:342
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:351
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.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:33
Use to initialize the QoS with the keep_all history setting.
Definition: qos.hpp:95
Use to initialize the QoS with the keep_last history setting and the given depth.
Definition: qos.hpp:101
Result type for checking QoS compatibility.
Definition: qos.hpp:302
QoSCompatibility compatibility
Compatibility result.
Definition: qos.hpp:304
std::string reason
Reason for a (possible) incompatibility.
Definition: qos.hpp:311
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:78
QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg, bool print_depth_warning=true)
Constructor which takes both a history policy and a depth (even if it would be unused).
Definition: qos.cpp:48
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:63