ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
qos.hpp
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 #ifndef RCLCPP__QOS_HPP_
16 #define RCLCPP__QOS_HPP_
17 
18 #include <string>
19 
20 #include "rclcpp/duration.hpp"
21 #include "rclcpp/exceptions.hpp"
22 #include "rclcpp/visibility_control.hpp"
23 #include "rcl/logging_rosout.h"
24 #include "rmw/incompatible_qos_events_statuses.h"
25 #include "rmw/qos_profiles.h"
26 #include "rmw/types.h"
27 
28 namespace rclcpp
29 {
30 
31 RCLCPP_PUBLIC
32 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind);
33 
34 enum class HistoryPolicy
35 {
36  KeepLast = RMW_QOS_POLICY_HISTORY_KEEP_LAST,
37  KeepAll = RMW_QOS_POLICY_HISTORY_KEEP_ALL,
38  SystemDefault = RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT,
39  Unknown = RMW_QOS_POLICY_HISTORY_UNKNOWN,
40 };
41 
42 enum class ReliabilityPolicy
43 {
44  BestEffort = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
45  Reliable = RMW_QOS_POLICY_RELIABILITY_RELIABLE,
46  SystemDefault = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT,
47  Unknown = RMW_QOS_POLICY_RELIABILITY_UNKNOWN,
48 };
49 
50 enum class DurabilityPolicy
51 {
52  Volatile = RMW_QOS_POLICY_DURABILITY_VOLATILE,
53  TransientLocal = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
54  SystemDefault = RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT,
55  Unknown = RMW_QOS_POLICY_DURABILITY_UNKNOWN,
56 };
57 
58 enum class LivelinessPolicy
59 {
60  Automatic = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
61  ManualByTopic = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC,
62  SystemDefault = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
63  Unknown = RMW_QOS_POLICY_LIVELINESS_UNKNOWN,
64 };
65 
66 enum class QoSCompatibility
67 {
68  Ok = RMW_QOS_COMPATIBILITY_OK,
69  Warning = RMW_QOS_COMPATIBILITY_WARNING,
70  Error = RMW_QOS_COMPATIBILITY_ERROR,
71 };
72 
74 struct RCLCPP_PUBLIC QoSInitialization
75 {
76  rmw_qos_history_policy_t history_policy;
77  size_t depth;
78 
80  QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg);
81 
83  static
85  from_rmw(const rmw_qos_profile_t & rmw_qos);
86 };
87 
89 struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization
90 {
91  KeepAll();
92 };
93 
95 struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization
96 {
97  explicit KeepLast(size_t depth);
98 };
99 
101 
110 class RCLCPP_PUBLIC QoS
111 {
112 public:
114 
127  explicit
128  QoS(
129  const QoSInitialization & qos_initialization,
130  const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
131 
133 
140  // cppcheck-suppress noExplicitConstructor
141  QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
142 
144  rmw_qos_profile_t &
145  get_rmw_qos_profile();
146 
148  const rmw_qos_profile_t &
149  get_rmw_qos_profile() const;
150 
152  QoS &
153  history(HistoryPolicy history);
154 
156  QoS &
157  history(rmw_qos_history_policy_t history);
158 
160  QoS &
161  keep_last(size_t depth);
162 
164  QoS &
165  keep_all();
166 
168  QoS &
169  reliability(rmw_qos_reliability_policy_t reliability);
170 
172  QoS &
173  reliability(ReliabilityPolicy reliability);
174 
176  QoS &
177  reliable();
178 
180  QoS &
181  best_effort();
182 
184  QoS &
185  durability(rmw_qos_durability_policy_t durability);
186 
188  QoS &
189  durability(DurabilityPolicy durability);
190 
192 
195  QoS &
196  durability_volatile();
197 
199  QoS &
200  transient_local();
201 
203  QoS &
204  deadline(rmw_time_t deadline);
205 
207  QoS &
208  deadline(const rclcpp::Duration & deadline);
209 
211  QoS &
212  lifespan(rmw_time_t lifespan);
213 
215  QoS &
216  lifespan(const rclcpp::Duration & lifespan);
217 
219  QoS &
220  liveliness(rmw_qos_liveliness_policy_t liveliness);
221 
223  QoS &
224  liveliness(LivelinessPolicy liveliness);
225 
227  QoS &
228  liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
229 
231  QoS &
232  liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
233 
235  QoS &
236  avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
237 
239  HistoryPolicy
240  history() const;
241 
243  size_t
244  depth() const;
245 
247  ReliabilityPolicy
248  reliability() const;
249 
251  DurabilityPolicy
252  durability() const;
253 
256  deadline() const;
257 
260  lifespan() const;
261 
263  LivelinessPolicy
264  liveliness() const;
265 
268  liveliness_lease_duration() const;
269 
271  bool
272  avoid_ros_namespace_conventions() const;
273 
274 private:
275  rmw_qos_profile_t rmw_qos_profile_;
276 };
277 
279 RCLCPP_PUBLIC
280 bool operator==(const QoS & left, const QoS & right);
281 RCLCPP_PUBLIC
282 bool operator!=(const QoS & left, const QoS & right);
283 
285 
289 {
291  QoSCompatibility compatibility;
292 
294 
298  std::string reason;
299 };
300 
302 
335 RCLCPP_PUBLIC
337 qos_check_compatible(const QoS & publisher_qos, const QoS & subscription_qos);
338 
351 class RCLCPP_PUBLIC ClockQoS : public QoS
352 {
353 public:
354  explicit
355  ClockQoS(
356  const QoSInitialization & qos_initialization = KeepLast(1));
357 };
358 
371 class RCLCPP_PUBLIC SensorDataQoS : public QoS
372 {
373 public:
374  explicit
376  const QoSInitialization & qos_initialization = (
377  QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
378  ));
379 };
380 
393 class RCLCPP_PUBLIC ParametersQoS : public QoS
394 {
395 public:
396  explicit
398  const QoSInitialization & qos_initialization = (
399  QoSInitialization::from_rmw(rmw_qos_profile_parameters)
400  ));
401 };
402 
415 class RCLCPP_PUBLIC ServicesQoS : public QoS
416 {
417 public:
418  explicit
419  ServicesQoS(
420  const QoSInitialization & qos_initialization = (
421  QoSInitialization::from_rmw(rmw_qos_profile_services_default)
422  ));
423 };
424 
437 class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
438 {
439 public:
440  explicit
442  const QoSInitialization & qos_initialization = (
443  QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
444  ));
445 };
446 
459 class RCLCPP_PUBLIC RosoutQoS : public QoS
460 {
461 public:
462  explicit
463  RosoutQoS(
464  const QoSInitialization & rosout_qos_initialization = (
465  QoSInitialization::from_rmw(rcl_qos_profile_rosout_default)
466  ));
467 };
468 
481 class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
482 {
483 public:
484  explicit
486  const QoSInitialization & qos_initialization = (
487  QoSInitialization::from_rmw(rmw_qos_profile_system_default)
488  ));
489 };
490 
491 } // namespace rclcpp
492 
493 #endif // RCLCPP__QOS_HPP_
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
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
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