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 
59  explicit NodeOptions(rcl_allocator_t allocator = rcl_get_default_allocator());
60 
63  virtual
64  ~NodeOptions() = default;
65 
68  NodeOptions(const NodeOptions & other);
69 
72  NodeOptions &
73  operator=(const NodeOptions & other);
74 
76 
85  const rcl_node_options_t *
86  get_rcl_node_options() const;
87 
90  rclcpp::Context::SharedPtr
91  context() const;
92 
95  NodeOptions &
96  context(rclcpp::Context::SharedPtr context);
97 
101  arguments() const;
102 
104 
111  NodeOptions &
113 
118 
121  parameter_overrides() const;
122 
124 
130  NodeOptions &
132 
134  template<typename ParameterT>
135  NodeOptions &
136  append_parameter_override(const std::string & name, const ParameterT & value)
137  {
139  return *this;
140  }
141 
144  bool
145  use_global_arguments() const;
146 
148 
156  NodeOptions &
158 
161  bool
162  enable_rosout() const;
163 
165 
172  NodeOptions &
174 
177  bool
178  use_intra_process_comms() const;
179 
181 
191  NodeOptions &
193 
196  bool
197  enable_topic_statistics() const;
198 
200 
208  NodeOptions &
210 
213  bool
214  start_parameter_services() const;
215 
217 
227  NodeOptions &
229 
232  bool
234 
236 
243  NodeOptions &
245 
248  const rclcpp::QoS &
249  parameter_event_qos() const;
250 
252 
256  NodeOptions &
258 
263 
265 
273  NodeOptions &
276 
279  bool
281 
283 
293  NodeOptions &
295 
298  bool
300 
302 
313  NodeOptions &
316 
319  const rcl_allocator_t &
320  allocator() const;
321 
323 
327  NodeOptions &
328  allocator(rcl_allocator_t allocator);
329 
330 protected:
332  size_t
333  get_domain_id_from_env() const;
334 
335 private:
336  // This is mutable to allow for a const accessor which lazily creates the node options instance.
338  mutable std::unique_ptr<rcl_node_options_t, void (*)(rcl_node_options_t *)> node_options_;
339 
340  // IMPORTANT: if any of these default values are changed, please update the
341  // documentation in this class.
342 
343  rclcpp::Context::SharedPtr context_ {
345 
346  std::vector<std::string> arguments_ {};
347 
348  std::vector<rclcpp::Parameter> parameter_overrides_ {};
349 
350  bool use_global_arguments_ {true};
351 
352  bool enable_rosout_ {true};
353 
354  bool use_intra_process_comms_ {false};
355 
356  bool enable_topic_statistics_ {false};
357 
358  bool start_parameter_services_ {true};
359 
360  bool start_parameter_event_publisher_ {true};
361 
362  rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
363  rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
364  );
365 
366  rclcpp::PublisherOptionsBase parameter_event_publisher_options_ = rclcpp::PublisherOptionsBase();
367 
368  bool allow_undeclared_parameters_ {false};
369 
370  bool automatically_declare_parameters_from_overrides_ {false};
371 
372  rcl_allocator_t allocator_ {rcl_get_default_allocator()};
373 };
374 
375 } // namespace rclcpp
376 
377 #endif // RCLCPP__NODE_OPTIONS_HPP_
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.
std::vector< std::string >
context.hpp
rcl_node_options_t
rclcpp::PublisherOptionsBase
Non-templated part of PublisherOptionsWithAllocator<Allocator>.
Definition: publisher_options.hpp:36
rclcpp::NodeOptions::context
rclcpp::Context::SharedPtr context() const
Return the context to be used by the node.
rclcpp::contexts::get_global_default_context
DefaultContext::SharedPtr get_global_default_context()
Definition: default_context.hpp:49
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:59
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::get_domain_id_from_env
size_t get_domain_id_from_env() const
Retrieve the ROS_DOMAIN_ID environment variable and populate options.
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)
visibility_control.hpp
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:242
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:136