rclcpp  master
C++ ROS Client Library API
node_options.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__NODE_OPTIONS_HPP_
16 #define RCLCPP__NODE_OPTIONS_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "rcl/node_options.h"
23 #include "rclcpp/context.hpp"
25 #include "rclcpp/parameter.hpp"
27 #include "rclcpp/qos.hpp"
29 
30 namespace rclcpp
31 {
32 
35 {
36 public:
38 
63 
66  virtual
67  ~NodeOptions() = default;
68 
71  NodeOptions(const NodeOptions & other);
72 
75  NodeOptions &
76  operator=(const NodeOptions & other);
77 
79 
88  const rcl_node_options_t *
89  get_rcl_node_options() const;
90 
93  rclcpp::Context::SharedPtr
94  context() const;
95 
98  NodeOptions &
99  context(rclcpp::Context::SharedPtr context);
100 
104  arguments() const;
105 
107 
114  NodeOptions &
116 
121 
124  parameter_overrides() const;
125 
127 
133  NodeOptions &
135 
137  template<typename ParameterT>
138  NodeOptions &
139  append_parameter_override(const std::string & name, const ParameterT & value)
140  {
142  return *this;
143  }
144 
147  bool
148  use_global_arguments() const;
149 
151 
159  NodeOptions &
161 
164  bool
165  enable_rosout() const;
166 
168 
175  NodeOptions &
177 
180  bool
181  use_intra_process_comms() const;
182 
184 
194  NodeOptions &
196 
199  bool
200  enable_topic_statistics() const;
201 
203 
211  NodeOptions &
213 
216  bool
217  start_parameter_services() const;
218 
220 
230  NodeOptions &
232 
235  bool
237 
239 
246  NodeOptions &
248 
251  const rclcpp::QoS &
252  clock_qos() const;
253 
255 
259  NodeOptions &
261 
262 
265  bool
266  use_clock_thread() const;
267 
269 
273  NodeOptions &
275 
278  const rclcpp::QoS &
279  parameter_event_qos() const;
280 
282 
286  NodeOptions &
288 
291  const rclcpp::QoS &
292  rosout_qos() const;
293 
295 
299  NodeOptions &
301 
306 
308 
316  NodeOptions &
319 
322  bool
324 
326 
336  NodeOptions &
338 
341  bool
343 
345 
356  NodeOptions &
359 
362  const rcl_allocator_t &
363  allocator() const;
364 
366 
370  NodeOptions &
372 
373 private:
374  // This is mutable to allow for a const accessor which lazily creates the node options instance.
376  mutable std::unique_ptr<rcl_node_options_t, void (*)(rcl_node_options_t *)> node_options_;
377 
378  // IMPORTANT: if any of these default values are changed, please update the
379  // documentation in this class.
380 
381  rclcpp::Context::SharedPtr context_ {
383 
384  std::vector<std::string> arguments_ {};
385 
386  std::vector<rclcpp::Parameter> parameter_overrides_ {};
387 
388  bool use_global_arguments_ {true};
389 
390  bool enable_rosout_ {true};
391 
392  bool use_intra_process_comms_ {false};
393 
394  bool enable_topic_statistics_ {false};
395 
396  bool start_parameter_services_ {true};
397 
398  bool start_parameter_event_publisher_ {true};
399 
400  rclcpp::QoS clock_qos_ = rclcpp::ClockQoS();
401 
402  bool use_clock_thread_ {true};
403 
404  rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
405  rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
406  );
407 
408  rclcpp::QoS rosout_qos_ = rclcpp::RosoutQoS();
409 
410  rclcpp::PublisherOptionsBase parameter_event_publisher_options_ = rclcpp::PublisherOptionsBase();
411 
412  bool allow_undeclared_parameters_ {false};
413 
414  bool automatically_declare_parameters_from_overrides_ {false};
415 
417 };
418 
419 } // namespace rclcpp
420 
421 #endif // RCLCPP__NODE_OPTIONS_HPP_
node_options.h
rcl_get_default_allocator
#define rcl_get_default_allocator
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::string
rclcpp::NodeOptions::use_global_arguments
bool use_global_arguments() const
Return the use_global_arguments flag.
rclcpp::NodeOptions::start_parameter_event_publisher
bool start_parameter_event_publisher() const
Return the start_parameter_event_publisher flag.
rclcpp::ClockQoS
Definition: qos.hpp:351
rclcpp::NodeOptions::use_clock_thread
bool use_clock_thread() const
Return the use_clock_thread flag.
std::vector< std::string >
context.hpp
rcl_node_options_t
rclcpp::PublisherOptionsBase
Non-templated part of PublisherOptionsWithAllocator<Allocator>.
Definition: publisher_options.hpp:37
rclcpp::NodeOptions::context
rclcpp::Context::SharedPtr context() const
Return the context to be used by the node.
rclcpp::NodeOptions::rosout_qos
const rclcpp::QoS & rosout_qos() const
Return a reference to the rosout QoS.
rclcpp::contexts::get_global_default_context
DefaultContext::SharedPtr get_global_default_context()
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
qos.hpp
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::NodeOptions::parameter_event_publisher_options
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options() const
Return a reference to the parameter_event_publisher_options.
rclcpp::NodeOptions::enable_topic_statistics
bool enable_topic_statistics() const
Return the enable_topic_statistics flag.
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.
publisher_options.hpp
rclcpp::NodeOptions::allow_undeclared_parameters
bool allow_undeclared_parameters() const
Return the allow_undeclared_parameters flag.
rclcpp::NodeOptions::operator=
NodeOptions & operator=(const NodeOptions &other)
Assignment operator.
rclcpp::NodeOptions::start_parameter_services
bool start_parameter_services() const
Return the start_parameter_services flag.
rclcpp::NodeOptions::use_intra_process_comms
bool use_intra_process_comms() const
Return the use_intra_process_comms flag.
rclcpp::NodeOptions::arguments
const std::vector< std::string > & arguments() const
Return a reference to the list of arguments for the node.
rclcpp::NodeOptions::allocator
const rcl_allocator_t & allocator() const
Return the rcl_allocator_t to be used.
rclcpp::NodeOptions::enable_rosout
bool enable_rosout() const
Return the enable_rosout flag.
parameter.hpp
default_context.hpp
std::vector::emplace_back
T emplace_back(T... args)
rcutils_allocator_t
visibility_control.hpp
rclcpp::NodeOptions::clock_qos
const rclcpp::QoS & clock_qos() const
Return a reference to the clock QoS.
rclcpp::NodeOptions
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
rclcpp::NodeOptions::automatically_declare_parameters_from_overrides
bool automatically_declare_parameters_from_overrides() const
Return the automatically_declare_parameters_from_overrides flag.
rclcpp::NodeOptions::NodeOptions
NodeOptions(rcl_allocator_t allocator=rcl_get_default_allocator())
Create NodeOptions with default values, optionally specifying the allocator to use.
rclcpp::ParameterEventsQoS
Definition: qos.hpp:437
rclcpp::NodeOptions::~NodeOptions
virtual ~NodeOptions()=default
Destructor.
rclcpp::NodeOptions::parameter_event_qos
const rclcpp::QoS & parameter_event_qos() const
Return a reference to the parameter_event_qos QoS.
std::unique_ptr
rclcpp::NodeOptions::get_rcl_node_options
const rcl_node_options_t * get_rcl_node_options() const
Return the rcl_node_options used by the node.
rclcpp::NodeOptions::parameter_overrides
std::vector< rclcpp::Parameter > & parameter_overrides()
Return a reference to the list of parameter overrides.
rclcpp::NodeOptions::append_parameter_override
NodeOptions & append_parameter_override(const std::string &name, const ParameterT &value)
Append a single parameter override, parameter idiom style.
Definition: node_options.hpp:139
rclcpp::RosoutQoS
Definition: qos.hpp:459