forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathnode_options.hpp
More file actions
421 lines (354 loc) · 13 KB
/
node_options.hpp
File metadata and controls
421 lines (354 loc) · 13 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
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
// 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__NODE_OPTIONS_HPP_
#define RCLCPP__NODE_OPTIONS_HPP_
#include <memory>
#include <string>
#include <vector>
#include "rcl/node_options.h"
#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
{
/// Encapsulation of options for node initialization.
class NodeOptions
{
public:
/// Create NodeOptions with default values, optionally specifying the allocator to use.
/**
* Default values for the node options:
*
* - context = rclcpp::contexts::get_global_default_context()
* - arguments = {}
* - parameter_overrides = {}
* - use_global_arguments = true
* - use_intra_process_comms = false
* - enable_topic_statistics = false
* - start_parameter_services = true
* - start_parameter_event_publisher = true
* - clock_qos = rclcpp::ClockQoS()
* - use_clock_thread = true
* - rosout_qos = rclcpp::RosoutQoS()
* - parameter_event_qos = rclcpp::ParameterEventQoS
* - with history setting and depth from rmw_qos_profile_parameter_events
* - parameter_event_publisher_options = rclcpp::PublisherOptionsBase
* - allow_undeclared_parameters = false
* - automatically_declare_parameters_from_overrides = false
* - allocator = rcl_get_default_allocator()
*
* \param[in] allocator allocator to use in construction of NodeOptions.
*/
RCLCPP_PUBLIC
explicit NodeOptions(rcl_allocator_t allocator = rcl_get_default_allocator());
/// Destructor.
RCLCPP_PUBLIC
virtual
~NodeOptions() = default;
/// Copy constructor.
RCLCPP_PUBLIC
NodeOptions(const NodeOptions & other);
/// Assignment operator.
RCLCPP_PUBLIC
NodeOptions &
operator=(const NodeOptions & other);
/// Return the rcl_node_options used by the node.
/**
* This data structure is created lazily, on the first call to this function.
* Repeated calls will not regenerate it unless one of the input settings
* changed, like arguments, use_global_arguments, or the rcl allocator.
*
* \return a const rcl_node_options_t structure used by the node
* \throws exceptions::UnknownROSArgsError if there are unknown ROS arguments
*/
RCLCPP_PUBLIC
const rcl_node_options_t *
get_rcl_node_options() const;
/// Return the context to be used by the node.
RCLCPP_PUBLIC
rclcpp::Context::SharedPtr
context() const;
/// Set the context, return this for parameter idiom.
RCLCPP_PUBLIC
NodeOptions &
context(rclcpp::Context::SharedPtr context);
/// Return a reference to the list of arguments for the node.
RCLCPP_PUBLIC
const std::vector<std::string> &
arguments() const;
/// Set the arguments, return this for parameter idiom.
/**
* These arguments are used to extract remappings used by the node and other
* ROS specific settings, as well as user defined non-ROS arguments.
*
* This will cause the internal rcl_node_options_t struct to be invalidated.
*/
RCLCPP_PUBLIC
NodeOptions &
arguments(const std::vector<std::string> & arguments);
/// Return a reference to the list of parameter overrides.
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter> &
parameter_overrides();
RCLCPP_PUBLIC
const std::vector<rclcpp::Parameter> &
parameter_overrides() const;
/// Set the parameters overrides, return this for parameter idiom.
/**
* These parameter overrides are used to change the initial value
* of declared parameters within the node, overriding hard coded default
* values if necessary.
*/
RCLCPP_PUBLIC
NodeOptions &
parameter_overrides(const std::vector<rclcpp::Parameter> & parameter_overrides);
/// Append a single parameter override, parameter idiom style.
template<typename ParameterT>
NodeOptions &
append_parameter_override(const std::string & name, const ParameterT & value)
{
this->parameter_overrides().emplace_back(name, rclcpp::ParameterValue(value));
return *this;
}
/// Return the use_global_arguments flag.
RCLCPP_PUBLIC
bool
use_global_arguments() const;
/// Set the use_global_arguments flag, return this for parameter idiom.
/**
* If true this will cause the node's behavior to be influenced by "global"
* arguments, i.e. arguments not targeted at specific nodes, as well as the
* arguments targeted at the current node.
*
* This will cause the internal rcl_node_options_t struct to be invalidated.
*/
RCLCPP_PUBLIC
NodeOptions &
use_global_arguments(bool use_global_arguments);
/// Return the enable_rosout flag.
RCLCPP_PUBLIC
bool
enable_rosout() const;
/// Set the enable_rosout flag, return this for parameter idiom.
/**
* If false this will cause the node not to use rosout logging.
*
* Defaults to true for now, as there are still some cases where it is
* desirable.
*/
RCLCPP_PUBLIC
NodeOptions &
enable_rosout(bool enable_rosout);
/// Return the use_intra_process_comms flag.
RCLCPP_PUBLIC
bool
use_intra_process_comms() const;
/// Set the use_intra_process_comms flag, return this for parameter idiom.
/**
* If true, messages on topics which are published and subscribed to within
* this context will go through a special intra-process communication code
* code path which can avoid serialization and deserialization, unnecessary
* copies, and achieve lower latencies in some cases.
*
* Defaults to false for now, as there are still some cases where it is not
* desirable.
*/
RCLCPP_PUBLIC
NodeOptions &
use_intra_process_comms(bool use_intra_process_comms);
/// Return the enable_topic_statistics flag.
RCLCPP_PUBLIC
bool
enable_topic_statistics() const;
/// Set the enable_topic_statistics flag, return this for parameter idiom.
/**
* If true, topic statistics collection and publication will be enabled
* for all subscriptions.
* This can be used to override the global topic statistics setting.
*
* Defaults to false.
*/
RCLCPP_PUBLIC
NodeOptions &
enable_topic_statistics(bool enable_topic_statistics);
/// Return the start_parameter_services flag.
RCLCPP_PUBLIC
bool
start_parameter_services() const;
/// Set the start_parameter_services flag, return this for parameter idiom.
/**
* If true, ROS services are created to allow external nodes to list, get,
* and request to set parameters of this node.
*
* If false, parameters will still work locally, but will not be accessible
* remotely.
*
* \sa start_parameter_event_publisher()
*/
RCLCPP_PUBLIC
NodeOptions &
start_parameter_services(bool start_parameter_services);
/// Return the start_parameter_event_publisher flag.
RCLCPP_PUBLIC
bool
start_parameter_event_publisher() const;
/// Set the start_parameter_event_publisher flag, return this for parameter idiom.
/**
* If true, a publisher is created on which an event message is published
* each time a parameter's state changes.
* This is used for recording and introspection, but is configurable
* separately from the other parameter services.
*/
RCLCPP_PUBLIC
NodeOptions &
start_parameter_event_publisher(bool start_parameter_event_publisher);
/// Return a reference to the clock QoS.
RCLCPP_PUBLIC
const rclcpp::QoS &
clock_qos() const;
/// Set the clock QoS.
/**
* The QoS settings to be used for the publisher on /clock topic, if enabled.
*/
RCLCPP_PUBLIC
NodeOptions &
clock_qos(const rclcpp::QoS & clock_qos);
/// Return the use_clock_thread flag.
RCLCPP_PUBLIC
bool
use_clock_thread() const;
/// Set the use_clock_thread flag, return this for parameter idiom.
/**
* If true, a dedicated thread will be used to subscribe to "/clock" topic.
*/
RCLCPP_PUBLIC
NodeOptions &
use_clock_thread(bool use_clock_thread);
/// Return a reference to the parameter_event_qos QoS.
RCLCPP_PUBLIC
const rclcpp::QoS &
parameter_event_qos() const;
/// Set the parameter_event_qos QoS, return this for parameter idiom.
/**
* The QoS settings to be used for the parameter event publisher, if enabled.
*/
RCLCPP_PUBLIC
NodeOptions &
parameter_event_qos(const rclcpp::QoS & parameter_event_qos);
/// Return a reference to the rosout QoS.
RCLCPP_PUBLIC
const rclcpp::QoS &
rosout_qos() const;
/// Set the rosout QoS.
/**
* The QoS settings to be used for the publisher on /rosout topic, if enabled.
*/
RCLCPP_PUBLIC
NodeOptions &
rosout_qos(const rclcpp::QoS & rosout_qos);
/// Return a reference to the parameter_event_publisher_options.
RCLCPP_PUBLIC
const rclcpp::PublisherOptionsBase &
parameter_event_publisher_options() const;
/// Set the parameter_event_publisher_options, return this for parameter idiom.
/**
* The QoS settings to be used for the parameter event publisher, if enabled.
*
* \todo(wjwwood): make this take/store an instance of
* rclcpp::PublisherOptionsWithAllocator<Allocator>, but to do that requires
* NodeOptions to also be templated based on the Allocator type.
*/
RCLCPP_PUBLIC
NodeOptions &
parameter_event_publisher_options(
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options);
/// Return the allow_undeclared_parameters flag.
RCLCPP_PUBLIC
bool
allow_undeclared_parameters() const;
/// Set the allow_undeclared_parameters, return this for parameter idiom.
/**
* If true, allow any parameter name to be set on the node without first
* being declared.
* Otherwise, setting an undeclared parameter will raise an exception.
*
* This option being true does not affect parameter_overrides, as the first
* set action will implicitly declare the parameter and therefore consider
* any parameter overrides.
*/
RCLCPP_PUBLIC
NodeOptions &
allow_undeclared_parameters(bool allow_undeclared_parameters);
/// Return the automatically_declare_parameters_from_overrides flag.
RCLCPP_PUBLIC
bool
automatically_declare_parameters_from_overrides() const;
/// Set the automatically_declare_parameters_from_overrides, return this.
/**
* If true, automatically iterate through the node's parameter overrides and
* implicitly declare any that have not already been declared.
* Otherwise, parameters passed to the node's parameter_overrides, and/or the
* global arguments (e.g. parameter overrides from a YAML file), which are
* not explicitly declared will not appear on the node at all, even if
* `allow_undeclared_parameters` is true.
* Already declared parameters will not be re-declared, and parameters
* declared in this way will use the default constructed ParameterDescriptor.
*/
RCLCPP_PUBLIC
NodeOptions &
automatically_declare_parameters_from_overrides(
bool automatically_declare_parameters_from_overrides);
/// Return the rcl_allocator_t to be used.
RCLCPP_PUBLIC
const rcl_allocator_t &
allocator() const;
/// Set the rcl_allocator_t to be used, may cause deallocation of existing rcl_node_options_t.
/**
* This will cause the internal rcl_node_options_t struct to be invalidated.
*/
RCLCPP_PUBLIC
NodeOptions &
allocator(rcl_allocator_t allocator);
private:
// This is mutable to allow for a const accessor which lazily creates the node options instance.
/// Underlying rcl_node_options structure.
mutable std::unique_ptr<rcl_node_options_t, void (*)(rcl_node_options_t *)> node_options_;
// IMPORTANT: if any of these default values are changed, please update the
// documentation in this class.
rclcpp::Context::SharedPtr context_ {
rclcpp::contexts::get_global_default_context()};
std::vector<std::string> arguments_ {};
std::vector<rclcpp::Parameter> parameter_overrides_ {};
bool use_global_arguments_ {true};
bool enable_rosout_ {true};
bool use_intra_process_comms_ {false};
bool enable_topic_statistics_ {false};
bool start_parameter_services_ {true};
bool start_parameter_event_publisher_ {true};
rclcpp::QoS clock_qos_ = rclcpp::ClockQoS();
bool use_clock_thread_ {true};
rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
);
rclcpp::QoS rosout_qos_ = rclcpp::RosoutQoS();
rclcpp::PublisherOptionsBase parameter_event_publisher_options_ = rclcpp::PublisherOptionsBase();
bool allow_undeclared_parameters_ {false};
bool automatically_declare_parameters_from_overrides_ {false};
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
};
} // namespace rclcpp
#endif // RCLCPP__NODE_OPTIONS_HPP_