Class NodeOptions

Class Documentation

class NodeOptions

Encapsulation of options for node initialization.

Public Functions

explicit NodeOptions(rcl_allocator_t allocator = rcl_get_default_allocator())

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

  • enable_rosout = 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()

Parameters:

allocator[in] allocator to use in construction of NodeOptions.

virtual ~NodeOptions() = default

Destructor.

NodeOptions(const NodeOptions &other)

Copy constructor.

NodeOptions &operator=(const NodeOptions &other)

Assignment operator.

const rcl_node_options_t *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.

Throws:

exceptions::UnknownROSArgsError – if there are unknown ROS arguments

Returns:

a const rcl_node_options_t structure used by the node

rclcpp::Context::SharedPtr context() const

Return the context to be used by the node.

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

Set the context, return this for parameter idiom.

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

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

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 ROS specific settings, as well as user defined non-ROS arguments.

This will cause the internal rcl_node_options_t struct to be invalidated.

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

Return a reference to the list of parameter overrides.

const std::vector<rclcpp::Parameter> &parameter_overrides() const
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.

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

Append a single parameter override, parameter idiom style.

bool use_global_arguments() const

Return the use_global_arguments flag.

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.

bool enable_rosout() const

Return the enable_rosout flag.

NodeOptions &enable_rosout(bool enable_rosout)

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.

bool use_intra_process_comms() const

Return the use_intra_process_comms flag.

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.

bool enable_topic_statistics() const

Return the enable_topic_statistics flag.

NodeOptions &enable_topic_statistics(bool enable_topic_statistics)

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.

bool start_parameter_services() const

Return the start_parameter_services flag.

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.

bool start_parameter_event_publisher() const

Return the start_parameter_event_publisher flag.

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.

const rclcpp::QoS &clock_qos() const

Return a reference to the clock QoS.

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

Set the clock QoS.

The QoS settings to be used for the publisher on /clock topic, if enabled.

bool use_clock_thread() const

Return the use_clock_thread flag.

NodeOptions &use_clock_thread(bool use_clock_thread)

Set the use_clock_thread flag, return this for parameter idiom.

If true, a dedicated thread will be used to subscribe to “/clock” topic.

const rclcpp::QoS &parameter_event_qos() const

Return a reference to the parameter_event_qos QoS.

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.

const rclcpp::QoS &rosout_qos() const

Return a reference to the rosout QoS.

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

Set the rosout QoS.

The QoS settings to be used for the publisher on /rosout topic, if enabled.

const rclcpp::PublisherOptionsBase &parameter_event_publisher_options() const

Return a reference to the parameter_event_publisher_options.

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.

bool allow_undeclared_parameters() const

Return the allow_undeclared_parameters flag.

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.

bool automatically_declare_parameters_from_overrides() const

Return the automatically_declare_parameters_from_overrides flag.

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. Parameter declaration from overrides is done in the node’s base constructor, so the user must take care to check if the parameter is already (e.g. automatically) declared before declaring it themselves. Already declared parameters will not be re-declared, and parameters declared in this way will use the default constructed ParameterDescriptor.

const rcl_allocator_t &allocator() const

Return the rcl_allocator_t to be used.

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.