ROS 2 rclcpp + rcl - kilted  kilted
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  BestAvailable = RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE,
48  Unknown = RMW_QOS_POLICY_RELIABILITY_UNKNOWN,
49 };
50 
51 enum class DurabilityPolicy
52 {
53  Volatile = RMW_QOS_POLICY_DURABILITY_VOLATILE,
54  TransientLocal = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
55  SystemDefault = RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT,
56  BestAvailable = RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE,
57  Unknown = RMW_QOS_POLICY_DURABILITY_UNKNOWN,
58 };
59 
60 enum class LivelinessPolicy
61 {
62  Automatic = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
63  ManualByTopic = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC,
64  SystemDefault = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
65  BestAvailable = RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE,
66  Unknown = RMW_QOS_POLICY_LIVELINESS_UNKNOWN,
67 };
68 
69 enum class QoSCompatibility
70 {
71  Ok = RMW_QOS_COMPATIBILITY_OK,
72  Warning = RMW_QOS_COMPATIBILITY_WARNING,
73  Error = RMW_QOS_COMPATIBILITY_ERROR,
74 };
75 
77 struct RCLCPP_PUBLIC QoSInitialization
78 {
79  rmw_qos_history_policy_t history_policy;
80  size_t depth;
81 
84  rmw_qos_history_policy_t history_policy_arg, size_t depth_arg,
85  bool print_depth_warning = true);
86 
88  static
90  from_rmw(const rmw_qos_profile_t & rmw_qos);
91 };
92 
94 struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization
95 {
96  KeepAll();
97 };
98 
100 struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization
101 {
102  explicit KeepLast(size_t depth, bool print_depth_warning = true);
103 };
104 
106 
115 class RCLCPP_PUBLIC QoS
116 {
117 public:
119 
132  explicit
133  QoS(
134  const QoSInitialization & qos_initialization,
135  const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
136 
138 
145  // cppcheck-suppress noExplicitConstructor
146  QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
147 
149 
153  rmw_qos_profile_t &
154  get_rmw_qos_profile();
155 
157 
161  const rmw_qos_profile_t &
162  get_rmw_qos_profile() const;
163 
165  QoS &
166  history(HistoryPolicy history);
167 
169  QoS &
170  history(rmw_qos_history_policy_t history);
171 
173  QoS &
174  keep_last(size_t depth);
175 
177  QoS &
178  keep_all();
179 
181  QoS &
182  reliability(rmw_qos_reliability_policy_t reliability);
183 
185  QoS &
186  reliability(ReliabilityPolicy reliability);
187 
189  QoS &
190  reliable();
191 
193  QoS &
194  best_effort();
195 
197  QoS &
198  reliability_best_available();
199 
201  QoS &
202  durability(rmw_qos_durability_policy_t durability);
203 
205  QoS &
206  durability(DurabilityPolicy durability);
207 
209 
212  QoS &
213  durability_volatile();
214 
216  QoS &
217  transient_local();
218 
220  QoS &
221  durability_best_available();
222 
224  QoS &
225  deadline(rmw_time_t deadline);
226 
228  QoS &
229  deadline(const rclcpp::Duration & deadline);
230 
232  QoS &
233  lifespan(rmw_time_t lifespan);
234 
236  QoS &
237  lifespan(const rclcpp::Duration & lifespan);
238 
240  QoS &
241  liveliness(rmw_qos_liveliness_policy_t liveliness);
242 
244  QoS &
245  liveliness(LivelinessPolicy liveliness);
246 
248  QoS &
249  liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
250 
252  QoS &
253  liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
254 
256  QoS &
257  avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
258 
260  HistoryPolicy
261  history() const;
262 
264  size_t
265  depth() const;
266 
268  ReliabilityPolicy
269  reliability() const;
270 
272  DurabilityPolicy
273  durability() const;
274 
277  deadline() const;
278 
281  lifespan() const;
282 
284  LivelinessPolicy
285  liveliness() const;
286 
289  liveliness_lease_duration() const;
290 
292  bool
293  avoid_ros_namespace_conventions() const;
294 
295 private:
296  rmw_qos_profile_t rmw_qos_profile_;
297 };
298 
300 RCLCPP_PUBLIC
301 bool operator==(const QoS & left, const QoS & right);
302 RCLCPP_PUBLIC
303 bool operator!=(const QoS & left, const QoS & right);
304 
306 
310 {
312  QoSCompatibility compatibility;
313 
315 
319  std::string reason;
320 };
321 
323 
356 RCLCPP_PUBLIC
358 qos_check_compatible(const QoS & publisher_qos, const QoS & subscription_qos);
359 
372 class RCLCPP_PUBLIC ClockQoS : public QoS
373 {
374 public:
375  explicit
376  ClockQoS(
377  const QoSInitialization & qos_initialization = KeepLast(1));
378 };
379 
392 class RCLCPP_PUBLIC SensorDataQoS : public QoS
393 {
394 public:
395  explicit
397  const QoSInitialization & qos_initialization = (
398  QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
399  ));
400 };
401 
414 class RCLCPP_PUBLIC ParametersQoS : public QoS
415 {
416 public:
417  explicit
419  const QoSInitialization & qos_initialization = (
420  QoSInitialization::from_rmw(rmw_qos_profile_parameters)
421  ));
422 };
423 
436 class RCLCPP_PUBLIC ServicesQoS : public QoS
437 {
438 public:
439  explicit
440  ServicesQoS(
441  const QoSInitialization & qos_initialization = (
442  QoSInitialization::from_rmw(rmw_qos_profile_services_default)
443  ));
444 };
445 
458 class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
459 {
460 public:
461  explicit
463  const QoSInitialization & qos_initialization = (
464  QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
465  ));
466 };
467 
480 class RCLCPP_PUBLIC RosoutQoS : public QoS
481 {
482 public:
483  explicit
484  RosoutQoS(
485  const QoSInitialization & rosout_qos_initialization = (
486  QoSInitialization::from_rmw(rmw_qos_profile_rosout_default)
487  ));
488 };
489 
502 class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
503 {
504 public:
505  explicit
507  const QoSInitialization & qos_initialization = (
508  QoSInitialization::from_rmw(rmw_qos_profile_system_default)
509  ));
510 };
511 
532 class RCLCPP_PUBLIC BestAvailableQoS : public QoS
533 {
534 public:
535  explicit
537  const QoSInitialization & qos_initialization = (
538  QoSInitialization::from_rmw(rmw_qos_profile_best_available)
539  ));
540 };
541 
542 } // namespace rclcpp
543 
544 #endif // RCLCPP__QOS_HPP_
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
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.
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:310
QoSCompatibility compatibility
Compatibility result.
Definition: qos.hpp:312
std::string reason
Reason for a (possible) incompatibility.
Definition: qos.hpp:319
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:78
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