rclcpp  master
C++ ROS Client Library API
qos.hpp
Go to the documentation of this file.
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"
23 #include "rmw/qos_profiles.h"
24 #include "rmw/types.h"
25 
26 namespace rclcpp
27 {
28 
30 
33 {
35  size_t depth;
36 
38  QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg);
39 
41  static
43  from_rmw(const rmw_qos_profile_t & rmw_qos);
44 };
45 
48 {
49  KeepAll();
50 };
51 
54 {
55  explicit KeepLast(size_t depth);
56 };
57 
60 {
61 public:
63  explicit
64  QoS(
65  const QoSInitialization & qos_initialization,
66  const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
67 
69 
72  // cppcheck-suppress noExplicitConstructor
73  QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
74 
77  get_rmw_qos_profile();
78 
80  const rmw_qos_profile_t &
81  get_rmw_qos_profile() const;
82 
84  QoS &
85  history(rmw_qos_history_policy_t history);
86 
88  QoS &
89  keep_last(size_t depth);
90 
92  QoS &
93  keep_all();
94 
96  QoS &
97  reliability(rmw_qos_reliability_policy_t reliability);
98 
100  QoS &
101  reliable();
102 
104  QoS &
105  best_effort();
106 
108  QoS &
109  durability(rmw_qos_durability_policy_t durability);
110 
112 
115  QoS &
116  durability_volatile();
117 
119  QoS &
120  transient_local();
121 
123  QoS &
124  deadline(rmw_time_t deadline);
125 
127  QoS &
128  deadline(const rclcpp::Duration & deadline);
129 
131  QoS &
132  lifespan(rmw_time_t lifespan);
133 
135  QoS &
136  lifespan(const rclcpp::Duration & lifespan);
137 
139  QoS &
140  liveliness(rmw_qos_liveliness_policy_t liveliness);
141 
143  QoS &
144  liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
145 
147  QoS &
148  liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
149 
151  QoS &
152  avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
153 
154 private:
155  rmw_qos_profile_t rmw_qos_profile_;
156 };
157 
160 bool operator==(const QoS & left, const QoS & right);
162 bool operator!=(const QoS & left, const QoS & right);
163 
177 {
178 public:
179  explicit
181  const QoSInitialization & qos_initialization = (
182  QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
183  ));
184 };
185 
199 {
200 public:
201  explicit
203  const QoSInitialization & qos_initialization = (
204  QoSInitialization::from_rmw(rmw_qos_profile_parameters)
205  ));
206 };
207 
221 {
222 public:
223  explicit
224  ServicesQoS(
225  const QoSInitialization & qos_initialization = (
226  QoSInitialization::from_rmw(rmw_qos_profile_services_default)
227  ));
228 };
229 
243 {
244 public:
245  explicit
247  const QoSInitialization & qos_initialization = (
248  QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
249  ));
250 };
251 
265 {
266 public:
267  explicit
269  const QoSInitialization & qos_initialization = (
270  QoSInitialization::from_rmw(rmw_qos_profile_system_default)
271  ));
272 };
273 
274 } // namespace rclcpp
275 
276 #endif // RCLCPP__QOS_HPP_
rclcpp::operator==
bool operator==(const QoS &left, const QoS &right)
Check if two QoS profiles are exactly equal in all policy values.
std::string
rmw_time_t
rclcpp::ServicesQoS
Definition: qos.hpp:220
rclcpp::KeepAll
Use to initialize the QoS with the keep_all history setting.
Definition: qos.hpp:47
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rmw_qos_liveliness_policy_t
enum RMW_PUBLIC_TYPE rmw_qos_liveliness_policy_t
rclcpp::QoSInitialization::depth
size_t depth
Definition: qos.hpp:35
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:59
rclcpp::QoSInitialization::from_rmw
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.
rmw_qos_history_policy_t
enum RMW_PUBLIC_TYPE rmw_qos_history_policy_t
rclcpp::SensorDataQoS
Definition: qos.hpp:176
rclcpp::SystemDefaultsQoS
Definition: qos.hpp:264
rmw_qos_policy_kind_t
enum RMW_PUBLIC_TYPE rmw_qos_policy_kind_t rmw_qos_policy_kind_t
rclcpp::Duration
Definition: duration.hpp:26
rclcpp::KeepLast
Use to initialize the QoS with the keep_last history setting and the given depth.
Definition: qos.hpp:53
rmw_qos_durability_policy_t
enum RMW_PUBLIC_TYPE rmw_qos_durability_policy_t
visibility_control.hpp
rclcpp::QoSInitialization
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:32
rmw_qos_profile_t
rclcpp::ParameterEventsQoS
Definition: qos.hpp:242
rmw_qos_reliability_policy_t
enum RMW_PUBLIC_TYPE rmw_qos_reliability_policy_t
types.h
rclcpp::ParametersQoS
Definition: qos.hpp:198
incompatible_qos_events_statuses.h
rclcpp::QoSInitialization::history_policy
rmw_qos_history_policy_t history_policy
Definition: qos.hpp:34
rclcpp::operator!=
bool operator!=(const QoS &left, const QoS &right)
duration.hpp
rclcpp::qos_policy_name_from_kind
std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind)
qos_profiles.h