rclcpp  master
C++ ROS Client Library API
Public Member Functions | Protected Member Functions | List of all members
rclcpp::NodeOptions Class Reference

Encapsulation of options for node initialization. More...

#include <node_options.hpp>

Public Member Functions

 NodeOptions (rcl_allocator_t allocator=rcl_get_default_allocator())
 Create NodeOptions with default values, optionally specifying the allocator to use. More...
 
virtual ~NodeOptions ()=default
 Destructor. More...
 
 NodeOptions (const NodeOptions &other)
 Copy constructor. More...
 
NodeOptionsoperator= (const NodeOptions &other)
 Assignment operator. More...
 
const rcl_node_options_tget_rcl_node_options () const
 Return the rcl_node_options used by the node. More...
 
rclcpp::Context::SharedPtr context () const
 Return the context to be used by the node. More...
 
NodeOptionscontext (rclcpp::Context::SharedPtr context)
 Set the context, return this for parameter idiom. More...
 
const std::vector< std::string > & arguments () const
 Return a reference to the list of arguments for the node. More...
 
NodeOptionsarguments (const std::vector< std::string > &arguments)
 Set the arguments, return this for parameter idiom. More...
 
std::vector< rclcpp::Parameter > & parameter_overrides ()
 Return a reference to the list of parameter overrides. More...
 
const std::vector< rclcpp::Parameter > & parameter_overrides () const
 
NodeOptionsparameter_overrides (const std::vector< rclcpp::Parameter > &parameter_overrides)
 Set the parameters overrides, return this for parameter idiom. More...
 
template<typename ParameterT >
NodeOptionsappend_parameter_override (const std::string &name, const ParameterT &value)
 Append a single parameter override, parameter idiom style. More...
 
bool use_global_arguments () const
 Return the use_global_arguments flag. More...
 
NodeOptionsuse_global_arguments (bool use_global_arguments)
 Set the use_global_arguments flag, return this for parameter idiom. More...
 
bool use_intra_process_comms () const
 Return the use_intra_process_comms flag. More...
 
NodeOptionsuse_intra_process_comms (bool use_intra_process_comms)
 Set the use_intra_process_comms flag, return this for parameter idiom. More...
 
bool start_parameter_services () const
 Return the start_parameter_services flag. More...
 
NodeOptionsstart_parameter_services (bool start_parameter_services)
 Set the start_parameter_services flag, return this for parameter idiom. More...
 
bool start_parameter_event_publisher () const
 Return the start_parameter_event_publisher flag. More...
 
NodeOptionsstart_parameter_event_publisher (bool start_parameter_event_publisher)
 Set the start_parameter_event_publisher flag, return this for parameter idiom. More...
 
const rclcpp::QoSparameter_event_qos () const
 Return a reference to the parameter_event_qos QoS. More...
 
NodeOptionsparameter_event_qos (const rclcpp::QoS &parameter_event_qos)
 Set the parameter_event_qos QoS, return this for parameter idiom. More...
 
const rclcpp::PublisherOptionsBaseparameter_event_publisher_options () const
 Return a reference to the parameter_event_publisher_options. More...
 
NodeOptionsparameter_event_publisher_options (const rclcpp::PublisherOptionsBase &parameter_event_publisher_options)
 Set the parameter_event_publisher_options, return this for parameter idiom. More...
 
bool allow_undeclared_parameters () const
 Return the allow_undeclared_parameters flag. More...
 
NodeOptionsallow_undeclared_parameters (bool allow_undeclared_parameters)
 Set the allow_undeclared_parameters, return this for parameter idiom. More...
 
bool automatically_declare_parameters_from_overrides () const
 Return the automatically_declare_parameters_from_overrides flag. More...
 
NodeOptionsautomatically_declare_parameters_from_overrides (bool automatically_declare_parameters_from_overrides)
 Set the automatically_declare_parameters_from_overrides, return this. More...
 
const rcl_allocator_tallocator () const
 Return the rcl_allocator_t to be used. More...
 
NodeOptionsallocator (rcl_allocator_t allocator)
 Set the rcl_allocator_t to be used, may cause deallocation of existing rcl_node_options_t. More...
 

Protected Member Functions

size_t get_domain_id_from_env () const
 Retrieve the ROS_DOMAIN_ID environment variable and populate options. More...
 

Detailed Description

Encapsulation of options for node initialization.

Constructor & Destructor Documentation

◆ NodeOptions() [1/2]

rclcpp::NodeOptions::NodeOptions ( rcl_allocator_t  allocator = rcl_get_default_allocator())
explicit

Create NodeOptions with default values, optionally specifying the allocator to use.

Default values for the node options:

Parameters
[in]allocatorallocator to use in construction of NodeOptions.

◆ ~NodeOptions()

virtual rclcpp::NodeOptions::~NodeOptions ( )
virtualdefault

Destructor.

◆ NodeOptions() [2/2]

rclcpp::NodeOptions::NodeOptions ( const NodeOptions other)

Copy constructor.

Member Function Documentation

◆ operator=()

NodeOptions& rclcpp::NodeOptions::operator= ( const NodeOptions other)

Assignment operator.

◆ get_rcl_node_options()

const rcl_node_options_t* rclcpp::NodeOptions::get_rcl_node_options ( ) const

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.

◆ context() [1/2]

rclcpp::Context::SharedPtr rclcpp::NodeOptions::context ( ) const

Return the context to be used by the node.

◆ context() [2/2]

NodeOptions& rclcpp::NodeOptions::context ( rclcpp::Context::SharedPtr  context)

Set the context, return this for parameter idiom.

◆ arguments() [1/2]

const std::vector<std::string>& rclcpp::NodeOptions::arguments ( ) const

Return a reference to the list of arguments for the node.

◆ arguments() [2/2]

NodeOptions& rclcpp::NodeOptions::arguments ( const std::vector< std::string > &  arguments)

Set the arguments, return this for parameter idiom.

These arguments are used to extract remappings used by the node and other settings.

This will cause the internal rcl_node_options_t struct to be invalidated.

◆ parameter_overrides() [1/3]

std::vector<rclcpp::Parameter>& rclcpp::NodeOptions::parameter_overrides ( )

Return a reference to the list of parameter overrides.

◆ parameter_overrides() [2/3]

const std::vector<rclcpp::Parameter>& rclcpp::NodeOptions::parameter_overrides ( ) const

◆ parameter_overrides() [3/3]

NodeOptions& rclcpp::NodeOptions::parameter_overrides ( const std::vector< rclcpp::Parameter > &  parameter_overrides)

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.

◆ append_parameter_override()

template<typename ParameterT >
NodeOptions& rclcpp::NodeOptions::append_parameter_override ( const std::string name,
const ParameterT &  value 
)
inline

Append a single parameter override, parameter idiom style.

◆ use_global_arguments() [1/2]

bool rclcpp::NodeOptions::use_global_arguments ( ) const

Return the use_global_arguments flag.

◆ use_global_arguments() [2/2]

NodeOptions& rclcpp::NodeOptions::use_global_arguments ( bool  use_global_arguments)

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.

◆ use_intra_process_comms() [1/2]

bool rclcpp::NodeOptions::use_intra_process_comms ( ) const

Return the use_intra_process_comms flag.

◆ use_intra_process_comms() [2/2]

NodeOptions& rclcpp::NodeOptions::use_intra_process_comms ( bool  use_intra_process_comms)

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.

◆ start_parameter_services() [1/2]

bool rclcpp::NodeOptions::start_parameter_services ( ) const

Return the start_parameter_services flag.

◆ start_parameter_services() [2/2]

NodeOptions& rclcpp::NodeOptions::start_parameter_services ( bool  start_parameter_services)

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.

See also
start_parameter_event_publisher()

◆ start_parameter_event_publisher() [1/2]

bool rclcpp::NodeOptions::start_parameter_event_publisher ( ) const

Return the start_parameter_event_publisher flag.

◆ start_parameter_event_publisher() [2/2]

NodeOptions& rclcpp::NodeOptions::start_parameter_event_publisher ( bool  start_parameter_event_publisher)

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.

◆ parameter_event_qos() [1/2]

const rclcpp::QoS& rclcpp::NodeOptions::parameter_event_qos ( ) const

Return a reference to the parameter_event_qos QoS.

◆ parameter_event_qos() [2/2]

NodeOptions& rclcpp::NodeOptions::parameter_event_qos ( const rclcpp::QoS parameter_event_qos)

Set the parameter_event_qos QoS, return this for parameter idiom.

The QoS settings to be used for the parameter event publisher, if enabled.

◆ parameter_event_publisher_options() [1/2]

const rclcpp::PublisherOptionsBase& rclcpp::NodeOptions::parameter_event_publisher_options ( ) const

Return a reference to the parameter_event_publisher_options.

◆ parameter_event_publisher_options() [2/2]

NodeOptions& rclcpp::NodeOptions::parameter_event_publisher_options ( const rclcpp::PublisherOptionsBase parameter_event_publisher_options)

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.

◆ allow_undeclared_parameters() [1/2]

bool rclcpp::NodeOptions::allow_undeclared_parameters ( ) const

Return the allow_undeclared_parameters flag.

◆ allow_undeclared_parameters() [2/2]

NodeOptions& rclcpp::NodeOptions::allow_undeclared_parameters ( bool  allow_undeclared_parameters)

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.

◆ automatically_declare_parameters_from_overrides() [1/2]

bool rclcpp::NodeOptions::automatically_declare_parameters_from_overrides ( ) const

Return the automatically_declare_parameters_from_overrides flag.

◆ automatically_declare_parameters_from_overrides() [2/2]

NodeOptions& rclcpp::NodeOptions::automatically_declare_parameters_from_overrides ( bool  automatically_declare_parameters_from_overrides)

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.

◆ allocator() [1/2]

const rcl_allocator_t& rclcpp::NodeOptions::allocator ( ) const

Return the rcl_allocator_t to be used.

◆ allocator() [2/2]

NodeOptions& rclcpp::NodeOptions::allocator ( rcl_allocator_t  allocator)

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.

◆ get_domain_id_from_env()

size_t rclcpp::NodeOptions::get_domain_id_from_env ( ) const
protected

Retrieve the ROS_DOMAIN_ID environment variable and populate options.


The documentation for this class was generated from the following file: