forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathqos.hpp
More file actions
276 lines (236 loc) · 7.21 KB
/
qos.hpp
File metadata and controls
276 lines (236 loc) · 7.21 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP__QOS_HPP_
#define RCLCPP__QOS_HPP_
#include <string>
#include "rclcpp/duration.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/incompatible_qos_events_statuses.h"
#include "rmw/qos_profiles.h"
#include "rmw/types.h"
namespace rclcpp
{
std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind);
/// QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
struct RCLCPP_PUBLIC QoSInitialization
{
rmw_qos_history_policy_t history_policy;
size_t depth;
/// Constructor which takes both a history policy and a depth (even if it would be unused).
QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg);
/// Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.
static
QoSInitialization
from_rmw(const rmw_qos_profile_t & rmw_qos);
};
/// Use to initialize the QoS with the keep_all history setting.
struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization
{
KeepAll();
};
/// Use to initialize the QoS with the keep_last history setting and the given depth.
struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization
{
explicit KeepLast(size_t depth);
};
/// Encapsulation of Quality of Service settings.
class RCLCPP_PUBLIC QoS
{
public:
/// Constructor which allows you to construct a QoS by giving the only required settings.
explicit
QoS(
const QoSInitialization & qos_initialization,
const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
/// Conversion constructor to ease construction in the common case of just specifying depth.
/**
* Convenience constructor, equivalent to QoS(KeepLast(history_depth)).
*/
// cppcheck-suppress noExplicitConstructor
QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
/// Return the rmw qos profile.
rmw_qos_profile_t &
get_rmw_qos_profile();
/// Return the rmw qos profile.
const rmw_qos_profile_t &
get_rmw_qos_profile() const;
/// Set the history policy.
QoS &
history(rmw_qos_history_policy_t history);
/// Set the history to keep last.
QoS &
keep_last(size_t depth);
/// Set the history to keep all.
QoS &
keep_all();
/// Set the reliability setting.
QoS &
reliability(rmw_qos_reliability_policy_t reliability);
/// Set the reliability setting to reliable.
QoS &
reliable();
/// Set the reliability setting to best effort.
QoS &
best_effort();
/// Set the durability setting.
QoS &
durability(rmw_qos_durability_policy_t durability);
/// Set the durability setting to volatile.
/**
* Note that this cannot be named `volatile` because it is a C++ keyword.
*/
QoS &
durability_volatile();
/// Set the durability setting to transient local.
QoS &
transient_local();
/// Set the deadline setting.
QoS &
deadline(rmw_time_t deadline);
/// Set the deadline setting, rclcpp::Duration.
QoS &
deadline(const rclcpp::Duration & deadline);
/// Set the lifespan setting.
QoS &
lifespan(rmw_time_t lifespan);
/// Set the lifespan setting, rclcpp::Duration.
QoS &
lifespan(const rclcpp::Duration & lifespan);
/// Set the liveliness setting.
QoS &
liveliness(rmw_qos_liveliness_policy_t liveliness);
/// Set the liveliness_lease_duration setting.
QoS &
liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
/// Set the liveliness_lease_duration setting, rclcpp::Duration.
QoS &
liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
/// Set the avoid_ros_namespace_conventions setting.
QoS &
avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
private:
rmw_qos_profile_t rmw_qos_profile_;
};
/// Check if two QoS profiles are exactly equal in all policy values.
RCLCPP_PUBLIC
bool operator==(const QoS & left, const QoS & right);
RCLCPP_PUBLIC
bool operator!=(const QoS & left, const QoS & right);
/**
* Sensor Data QoS class
* - History: Keep last,
* - Depth: 5,
* - Reliability: Best effort,
* - Durability: Volatile,
* - Deadline: Default,
* - Lifespan: Default,
* - Liveliness: System default,
* - Liveliness lease duration: default,
* - avoid ros namespace conventions: false
*/
class RCLCPP_PUBLIC SensorDataQoS : public QoS
{
public:
explicit
SensorDataQoS(
const QoSInitialization & qos_initialization = (
QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
));
};
/**
* Parameters QoS class
* - History: Keep last,
* - Depth: 1000,
* - Reliability: Reliable,
* - Durability: Volatile,
* - Deadline: Default,
* - Lifespan: Default,
* - Liveliness: System default,
* - Liveliness lease duration: default,
* - Avoid ros namespace conventions: false
*/
class RCLCPP_PUBLIC ParametersQoS : public QoS
{
public:
explicit
ParametersQoS(
const QoSInitialization & qos_initialization = (
QoSInitialization::from_rmw(rmw_qos_profile_parameters)
));
};
/**
* Services QoS class
* - History: Keep last,
* - Depth: 10,
* - Reliability: Reliable,
* - Durability: Volatile,
* - Deadline: Default,
* - Lifespan: Default,
* - Liveliness: System default,
* - Liveliness lease duration: default,
* - Avoid ros namespace conventions: false
*/
class RCLCPP_PUBLIC ServicesQoS : public QoS
{
public:
explicit
ServicesQoS(
const QoSInitialization & qos_initialization = (
QoSInitialization::from_rmw(rmw_qos_profile_services_default)
));
};
/**
* Parameter events QoS class
* - History: Keep last,
* - Depth: 1000,
* - Reliability: Reliable,
* - Durability: Volatile,
* - Deadline: Default,
* - Lifespan: Default,
* - Liveliness: System default,
* - Liveliness lease duration: default,
* - Avoid ros namespace conventions: false
*/
class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
{
public:
explicit
ParameterEventsQoS(
const QoSInitialization & qos_initialization = (
QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
));
};
/**
* System defaults QoS class
* - History: System default,
* - Depth: System default,
* - Reliability: System default,
* - Durability: System default,
* - Deadline: Default,
* - Lifespan: Default,
* - Liveliness: System default,
* - Liveliness lease duration: System default,
* - Avoid ros namespace conventions: false
*/
class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
{
public:
explicit
SystemDefaultsQoS(
const QoSInitialization & qos_initialization = (
QoSInitialization::from_rmw(rmw_qos_profile_system_default)
));
};
} // namespace rclcpp
#endif // RCLCPP__QOS_HPP_