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 <rmw/qos_profiles.h>
19 #include <rmw/types.h>
20 
21 #include "rclcpp/duration.hpp"
23 
24 namespace rclcpp
25 {
26 
29 {
31  size_t depth;
32 
34  QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg);
35 
37  static
39  from_rmw(const rmw_qos_profile_t & rmw_qos);
40 };
41 
44 {
45  KeepAll();
46 };
47 
50 {
51  explicit KeepLast(size_t depth);
52 };
53 
56 {
57 public:
59  explicit
60  QoS(
61  const QoSInitialization & qos_initialization,
62  const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
63 
65 
68  // cppcheck-suppress noExplicitConstructor
69  QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
70 
73  get_rmw_qos_profile();
74 
76  const rmw_qos_profile_t &
77  get_rmw_qos_profile() const;
78 
80  QoS &
81  history(rmw_qos_history_policy_t history);
82 
84  QoS &
85  keep_last(size_t depth);
86 
88  QoS &
89  keep_all();
90 
92  QoS &
93  reliability(rmw_qos_reliability_policy_t reliability);
94 
96  QoS &
97  reliable();
98 
100  QoS &
101  best_effort();
102 
104  QoS &
105  durability(rmw_qos_durability_policy_t durability);
106 
108 
111  QoS &
112  durability_volatile();
113 
115  QoS &
116  transient_local();
117 
119  QoS &
120  deadline(rmw_time_t deadline);
121 
123  QoS &
124  deadline(const rclcpp::Duration & deadline);
125 
127  QoS &
128  lifespan(rmw_time_t lifespan);
129 
131  QoS &
132  lifespan(const rclcpp::Duration & lifespan);
133 
135  QoS &
136  liveliness(rmw_qos_liveliness_policy_t liveliness);
137 
139  QoS &
140  liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
141 
143  QoS &
144  liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
145 
147  QoS &
148  avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
149 
150 private:
151  rmw_qos_profile_t rmw_qos_profile_;
152 };
153 
155 {
156 public:
157  explicit
159  const QoSInitialization & qos_initialization = (
160  QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
161  ));
162 };
163 
165 {
166 public:
167  explicit
169  const QoSInitialization & qos_initialization = (
170  QoSInitialization::from_rmw(rmw_qos_profile_parameters)
171  ));
172 };
173 
175 {
176 public:
177  explicit
178  ServicesQoS(
179  const QoSInitialization & qos_initialization = (
180  QoSInitialization::from_rmw(rmw_qos_profile_services_default)
181  ));
182 };
183 
185 {
186 public:
187  explicit
189  const QoSInitialization & qos_initialization = (
190  QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
191  ));
192 };
193 
195 {
196 public:
197  explicit
199  const QoSInitialization & qos_initialization = (
200  QoSInitialization::from_rmw(rmw_qos_profile_system_default)
201  ));
202 };
203 
204 } // namespace rclcpp
205 
206 #endif // RCLCPP__QOS_HPP_
Use to initialize the QoS with the keep_all history setting.
Definition: qos.hpp:43
Encapsulation of Quality of Service settings.
Definition: qos.hpp:55
Definition: qos.hpp:174
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
enum RMW_PUBLIC_TYPE rmw_qos_history_policy_t
Definition: qos.hpp:184
Use to initialize the QoS with the keep_last history setting and the given depth. ...
Definition: qos.hpp:49
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: duration.hpp:26
enum RMW_PUBLIC_TYPE rmw_qos_durability_policy_t
size_t depth
Definition: qos.hpp:31
enum RMW_PUBLIC_TYPE rmw_qos_reliability_policy_t
Definition: qos.hpp:154
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Definition: qos.hpp:164
Definition: qos.hpp:194
rmw_qos_history_policy_t history_policy
Definition: qos.hpp:30
enum RMW_PUBLIC_TYPE rmw_qos_liveliness_policy_t
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:28