Class Node

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< Node >

Class Documentation

class Node : public std::enable_shared_from_this<Node>

Node is the single point of entry for creating publishers and subscribers.

Public Types

using PreSetParametersCallbackHandle = rclcpp::node_interfaces::PreSetParametersCallbackHandle
using PreSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType
using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle
using OnSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType
using OnParametersSetCallbackType = OnSetParametersCallbackType
using PostSetParametersCallbackHandle = rclcpp::node_interfaces::PostSetParametersCallbackHandle
using PostSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType

Public Functions

explicit Node(const std::string &node_name, const NodeOptions &options = NodeOptions())

Create a new node with the specified name.

Parameters:
  • node_name[in] Name of the node.

  • options[in] Additional options to control creation of the node.

Throws:

InvalidNamespaceError – if the namespace is invalid

explicit Node(const std::string &node_name, const std::string &namespace_, const NodeOptions &options = NodeOptions())

Create a new node with the specified name.

Parameters:
  • node_name[in] Name of the node.

  • namespace_[in] Namespace of the node.

  • options[in] Additional options to control creation of the node.

Throws:

InvalidNamespaceError – if the namespace is invalid

virtual ~Node()
const char *get_name() const

Get the name of the node.

Returns:

The name of the node.

const char *get_namespace() const

Get the namespace of the node.

This namespace is the “node’s” namespace, and therefore is not affected by any sub-namespace’s that may affect entities created with this instance. Use get_effective_namespace() to get the full namespace used by entities.

Returns:

The namespace of the node.

const char *get_fully_qualified_name() const

Get the fully-qualified name of the node.

The fully-qualified name includes the local namespace and name of the node.

Returns:

fully-qualified name of the node.

rclcpp::Logger get_logger() const

Get the logger of the node.

Returns:

The logger of the node.

rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node = true)

Create and return a callback group.

void for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction &func)

Iterate over the callback groups in the node, calling the given function on each valid one.

This method is called in a thread-safe way, and also makes sure to only call the given function on those items that are still valid.

Parameters:

func[in] The callback function to call on each valid callback group.

template<typename MessageT, typename AllocatorT = std::allocator<void>, typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT> create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator<AllocatorT> &options = PublisherOptionsWithAllocator<AllocatorT>())

Create and return a Publisher.

The rclcpp::QoS has several convenient constructors, including a conversion constructor for size_t, which mimics older API’s that allows just a string and size_t to create a publisher.

For example, all of these cases will work:

pub = node->create_publisher<MsgT>("chatter", 10);  // implicitly KeepLast
pub = node->create_publisher<MsgT>("chatter", QoS(10));  // implicitly KeepLast
pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().durability_volatile());
{
  rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
  pub = node->create_publisher<MsgT>("chatter", custom_qos);
}

The publisher options may optionally be passed as the third argument for any of the above cases.

Parameters:
  • topic_name[in] The topic for this publisher to publish on.

  • qos[in] The Quality of Service settings for the publisher.

  • options[in] Additional options for the created Publisher.

Returns:

Shared pointer to the created publisher.

template<typename MessageT, typename CallbackT, typename AllocatorT = std::allocator<void>, typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>, typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType>
std::shared_ptr<SubscriptionT> create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator<AllocatorT> &options = SubscriptionOptionsWithAllocator<AllocatorT>(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (MessageMemoryStrategyT::create_default()))

Create and return a Subscription.

Parameters:
  • topic_name[in] The topic to subscribe on.

  • qos[in] QoS profile for Subcription.

  • callback[in] The user-defined callback function to receive a message

  • options[in] Additional options for the creation of the Subscription.

  • msg_mem_strat[in] The message memory strategy to use for allocating messages.

Returns:

Shared pointer to the created subscription.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
rclcpp::WallTimer<CallbackT>::SharedPtr create_wall_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a wall timer that uses the wall clock to drive the callback.

Parameters:
  • period[in] Time interval between triggers of the callback.

  • callback[in] User-defined callback function.

  • group[in] Callback group to execute this timer’s callback in.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
rclcpp::GenericTimer<CallbackT>::SharedPtr create_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a timer that uses the node clock to drive the callback.

Parameters:
  • period[in] Time interval between triggers of the callback.

  • callback[in] User-defined callback function.

  • group[in] Callback group to execute this timer’s callback in.

template<typename ServiceT>
rclcpp::Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Client.

Deprecated:

use rclcpp::QoS instead of rmw_qos_profile_t

Parameters:
  • service_name[in] The topic to service on.

  • qos_profile[in] rmw_qos_profile_t Quality of service profile for client.

  • group[in] Callback group to call the service.

Returns:

Shared pointer to the created client.

template<typename ServiceT>
rclcpp::Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Client.

Parameters:
  • service_name[in] The name on which the service is accessible.

  • qos[in] Quality of service profile for client.

  • group[in] Callback group to handle the reply to service calls.

Returns:

Shared pointer to the created client.

template<typename ServiceT, typename CallbackT>
rclcpp::Service<ServiceT>::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Service.

Deprecated:

use rclcpp::QoS instead of rmw_qos_profile_t

Parameters:
  • service_name[in] The topic to service on.

  • callback[in] User-defined callback function.

  • qos_profile[in] rmw_qos_profile_t Quality of service profile for client.

  • group[in] Callback group to call the service.

Returns:

Shared pointer to the created service.

template<typename ServiceT, typename CallbackT>
rclcpp::Service<ServiceT>::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Service.

Parameters:
  • service_name[in] The topic to service on.

  • callback[in] User-defined callback function.

  • qos[in] Quality of service profile for the service.

  • group[in] Callback group to call the service.

Returns:

Shared pointer to the created service.

template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options = (rclcpp::PublisherOptionsWithAllocator<AllocatorT>()))

Create and return a GenericPublisher.

The returned pointer will never be empty, but this function can throw various exceptions, for instance when the message’s package can not be found on the AMENT_PREFIX_PATH.

Parameters:
  • topic_name[in] Topic name

  • topic_type[in] Topic type

  • qos[in] QoS settings

  • options – Publisher options. Not all publisher options are currently respected, the only relevant options for this publisher are event_callbacks, use_default_callbacks, and callback_group.

Returns:

Shared pointer to the created generic publisher.

template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &options = (rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()))

Create and return a GenericSubscription.

The returned pointer will never be empty, but this function can throw various exceptions, for instance when the message’s package can not be found on the AMENT_PREFIX_PATH.

Parameters:
  • topic_name[in] Topic name

  • topic_type[in] Topic type

  • qos[in] QoS settings

  • callback[in] Callback for new messages of serialized form

  • options[in] Subscription options. Not all subscription options are currently respected, the only relevant options for this subscription are event_callbacks, use_default_callbacks, ignore_local_publications, and callback_group.

Returns:

Shared pointer to the created generic subscription.

const rclcpp::ParameterValue &declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Declare and initialize a parameter, return the effective value.

This method is used to declare that a parameter exists on this node. If, at run-time, the user has provided an initial value then it will be set in this method, otherwise the given default_value will be set. In either case, the resulting value is returned, whether or not it is based on the default value or the user provided initial value.

If no parameter_descriptor is given, then the default values from the message definition will be used, e.g. read_only will be false.

The name and type in the given rcl_interfaces::msg::ParameterDescriptor are ignored, and should be specified using the name argument to this function and the default value’s type instead.

If ignore_override is true, the parameter override will be ignored.

This method will result in any callback registered with add_on_set_parameters_callback and add_post_set_parameters_callback to be called for the parameter being set.

If a callback was registered previously with add_on_set_parameters_callback, it will be called prior to setting the parameter for the node. If that callback prevents the initial value for the parameter from being set then rclcpp::exceptions::InvalidParameterValueException is thrown.

If a callback was registered previously with add_post_set_parameters_callback, it will be called after setting the parameter successfully for the node.

This method will not result in any callbacks registered with add_pre_set_parameters_callback to be called.

The returned reference will remain valid until the parameter is undeclared.

Parameters:
  • name[in] The name of the parameter.

  • default_value[in] An initial value to be used if at run-time user did not override it.

  • parameter_descriptor[in] An optional, custom description for the parameter.

  • ignore_override[in] When true, the parameter override is ignored. Default to false.

Throws:
Returns:

A const reference to the value of the parameter.

const rclcpp::ParameterValue &declare_parameter(const std::string &name, rclcpp::ParameterType type, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override = false)

Declare and initialize a parameter, return the effective value.

Same as the previous one, but a default value is not provided and the user must provide a parameter override of the correct type.

Parameters:
  • name[in] The name of the parameter.

  • type[in] Desired type of the parameter, which will enforced at runtime.

  • parameter_descriptor[in] An optional, custom description for the parameter.

  • ignore_override[in] When true, the parameter override is ignored. Default to false.

Throws:
  • Same – as the previous overload taking a default value.

  • rclcpp::exceptions::InvalidParameterTypeException – if an override is not provided or the provided override is of the wrong type.

Returns:

A const reference to the value of the parameter.

template<typename ParameterT>
auto declare_parameter(const std::string &name, const ParameterT &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Declare and initialize a parameter with a type.

See the non-templated declare_parameter() on this class for details.

If the type of the default value, and therefore also the type of return value, differs from the initial value provided in the node options, then a rclcpp::exceptions::InvalidParameterTypeException may be thrown. To avoid this, use the declare_parameter() method which returns an rclcpp::ParameterValue instead.

Note, this method cannot return a const reference, because extending the lifetime of a temporary only works recursively with member initializers, and cannot be extended to members of a class returned. The return value of this class is a copy of the member of a ParameterValue which is returned by the other version of declare_parameter(). See also:

template<typename ParameterT>
auto declare_parameter(const std::string &name, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Declare and initialize a parameter with a type.

See the non-templated declare_parameter() on this class for details.

template<typename ParameterT>
std::vector<ParameterT> declare_parameters(const std::string &namespace_, const std::map<std::string, ParameterT> &parameters, bool ignore_overrides = false)

Declare and initialize several parameters with the same namespace and type.

For each key in the map, a parameter with a name of “namespace.key” will be set to the value in the map. The resulting value for each declared parameter will be returned.

The name expansion is naive, so if you set the namespace to be “foo.”, then the resulting parameter names will be like “foo..key”. However, if the namespace is an empty string, then no leading ‘.’ will be placed before each key, which would have been the case when naively expanding “namespace.key”. This allows you to declare several parameters at once without a namespace.

The map contains default values for parameters. There is another overload which takes the std::pair with the default value and descriptor.

If ignore_overrides is true, all the overrides of the parameters declared by the function call will be ignored.

This method will result in any callback registered with add_on_set_parameters_callback and add_post_set_parameters_callback to be called once for each parameter.

This method, if successful, will result in any callback registered with add_on_set_parameters_callback to be called, once for each parameter. If that callback prevents the initial value for any parameter from being set then rclcpp::exceptions::InvalidParameterValueException is thrown.

If a callback was registered previously with add_post_set_parameters_callback, it will be called after setting the parameters successfully for the node, once for each parameter.

This method will not result in any callbacks registered with add_pre_set_parameters_callback to be called.

Parameters:
  • namespace_[in] The namespace in which to declare the parameters.

  • parameters[in] The parameters to set in the given namespace.

  • ignore_overrides[in] When true, the parameters overrides are ignored. Default to false.

Throws:
template<typename ParameterT>
std::vector<ParameterT> declare_parameters(const std::string &namespace_, const std::map<std::string, std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>> &parameters, bool ignore_overrides = false)

Declare and initialize several parameters with the same namespace and type.

This version will take a map where the value is a pair, with the default parameter value as the first item and a parameter descriptor as the second.

See the simpler declare_parameters() on this class for more details.

void undeclare_parameter(const std::string &name)

Undeclare a previously declared parameter.

This method will not cause a callback registered with any of the add_pre_set_parameters_callback, add_on_set_parameters_callback and add_post_set_parameters_callback to be called.

Parameters:

name[in] The name of the parameter to be undeclared.

Throws:
bool has_parameter(const std::string &name) const

Return true if a given parameter is declared.

Parameters:

name[in] The name of the parameter to check for being declared.

Returns:

true if the parameter name has been declared, otherwise false.

rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)

Set a single parameter.

Set the given parameter and then return result of the set action.

If the parameter has not been declared this function may throw the rclcpp::exceptions::ParameterNotDeclaredException exception, but only if the node was not created with the rclcpp::NodeOptions::allow_undeclared_parameters set to true. If undeclared parameters are allowed, then the parameter is implicitly declared with the default parameter meta data before being set. Parameter overrides are ignored by set_parameter.

This method will result in any callback registered with add_pre_set_parameters_callback, add_on_set_parameters_callbackand add_post_set_parameters_callback` to be called once for the parameter being set.

This method will result in any callback registered with add_on_set_parameters_callback to be called. If the callback prevents the parameter from being set, then it will be reflected in the SetParametersResult that is returned, but no exception will be thrown.

If a callback was registered previously with add_pre_set_parameters_callback, it will be called once prior to the validation of the parameter for the node. If this callback makes modified parameter list empty, then it will be reflected in the returned result; no exceptions will be raised in this case.

If a callback was registered previously with add_post_set_parameters_callback, it will be called once after setting the parameter successfully for the node.

If the value type of the parameter is rclcpp::PARAMETER_NOT_SET, and the existing parameter type is something else, then the parameter will be implicitly undeclared. This will result in a parameter event indicating that the parameter was deleted.

Parameters:

parameter[in] The parameter to be set.

Throws:

rclcpp::exceptions::ParameterNotDeclaredException – if the parameter has not been declared and undeclared parameters are not allowed.

Returns:

The result of the set action.

std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(const std::vector<rclcpp::Parameter> &parameters)

Set one or more parameters, one at a time.

Set the given parameters, one at a time, and then return result of each set action.

Parameters are set in the order they are given within the input vector.

Like set_parameter, if any of the parameters to be set have not first been declared, and undeclared parameters are not allowed (the default), then this method will throw rclcpp::exceptions::ParameterNotDeclaredException.

If setting a parameter fails due to not being declared, then the parameters which have already been set will stay set, and no attempt will be made to set the parameters which come after.

If a parameter fails to be set due to any other reason, like being rejected by the user’s callback (basically any reason other than not having been declared beforehand), then that is reflected in the corresponding SetParametersResult in the vector returned by this function.

This method will result in any callback registered with add_pre_set_parameters_callback, add_on_set_parameters_callback and add_post_set_parameters_callback to be called once for each parameter.

If a callback was registered previously with add_pre_set_parameters_callback, it will be called prior to the validation of parameters for the node, once for each parameter. If this callback makes modified parameter list empty, then it will be reflected in the returned result; no exceptions will be raised in this case.

This method will result in any callback registered with add_on_set_parameters_callback to be called, once for each parameter. If the callback prevents the parameter from being set, then, as mentioned before, it will be reflected in the corresponding SetParametersResult that is returned, but no exception will be thrown.

If a callback was registered previously with add_post_set_parameters_callback, it will be called after setting the parameters successfully for the node, once for each parameter.

Like set_parameter() this method will implicitly undeclare parameters with the type rclcpp::PARAMETER_NOT_SET.

Parameters:

parameters[in] The vector of parameters to be set.

Throws:

rclcpp::exceptions::ParameterNotDeclaredException – if any parameter has not been declared and undeclared parameters are not allowed.

Returns:

The results for each set action as a vector.

rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector<rclcpp::Parameter> &parameters)

Set one or more parameters, all at once.

Set the given parameters, all at one time, and then aggregate result.

Behaves like set_parameter, except that it sets multiple parameters, failing all if just one of the parameters are unsuccessfully set. Either all of the parameters are set or none of them are set.

Like set_parameter and set_parameters, this method may throw an rclcpp::exceptions::ParameterNotDeclaredException exception if any of the parameters to be set have not first been declared. If the exception is thrown then none of the parameters will have been set.

This method will result in any callback registered with add_pre_set_parameters_callback, add_on_set_parameters_callback and add_post_set_parameters_callback to be called only ‘once’ for all parameters.

If a callback was registered previously with add_pre_set_parameters_callback, it will be called prior to the validation of node parameters, just one time for all parameters. If this callback makes modified parameter list empty, then it will be reflected in the returned result; no exceptions will be raised in this case.

This method will result in any callback registered with ‘add_on_set_parameters_callback’ to be called, just one time. If the callback prevents the parameters from being set, then it will be reflected in the SetParametersResult which is returned, but no exception will be thrown.

If a callback was registered previously with add_post_set_parameters_callback, it will be called after setting the node parameters successfully, just one time for all parameters.

If you pass multiple rclcpp::Parameter instances with the same name, then only the last one in the vector (forward iteration) will be set.

Like set_parameter() this method will implicitly undeclare parameters with the type rclcpp::PARAMETER_NOT_SET.

Parameters:

parameters[in] The vector of parameters to be set.

Throws:

rclcpp::exceptions::ParameterNotDeclaredException – if any parameter has not been declared and undeclared parameters are not allowed.

Returns:

The aggregate result of setting all the parameters atomically.

rclcpp::Parameter get_parameter(const std::string &name) const

Return the parameter by the given name.

If the parameter has not been declared, then this method may throw the rclcpp::exceptions::ParameterNotDeclaredException exception. If the parameter has not been initialized, then this method may throw the rclcpp::exceptions::ParameterUninitializedException exception.

If undeclared parameters are allowed, see the node option rclcpp::NodeOptions::allow_undeclared_parameters, then this method will not throw the rclcpp::exceptions::ParameterNotDeclaredException exception, and instead return a default initialized rclcpp::Parameter, which has a type of rclcpp::ParameterType::PARAMETER_NOT_SET.

Parameters:

name[in] The name of the parameter to get.

Throws:
Returns:

The requested parameter inside of a rclcpp parameter object.

bool get_parameter(const std::string &name, rclcpp::Parameter &parameter) const

Get the value of a parameter by the given name, and return true if it was set.

This method will never throw the rclcpp::exceptions::ParameterNotDeclaredException exception, but will instead return false if the parameter has not be previously declared.

If the parameter was not declared, then the output argument for this method which is called “parameter” will not be assigned a value. If the parameter was declared, and therefore has a value, then it is assigned into the “parameter” argument of this method.

Parameters:
  • name[in] The name of the parameter to get.

  • parameter[out] The output storage for the parameter being retrieved.

Returns:

true if the parameter was previously declared, otherwise false.

template<typename ParameterT>
bool get_parameter(const std::string &name, ParameterT &parameter) const

Get the value of a parameter by the given name, and return true if it was set.

Identical to the non-templated version of this method, except that when assigning the output argument called “parameter”, this method will attempt to coerce the parameter value into the type requested by the given template argument, which may fail and throw an exception.

If the parameter has not been declared, it will not attempt to coerce the value into the requested type, as it is known that the type is not set.

Throws:

rclcpp::ParameterTypeException – if the requested type does not match the value of the parameter which is stored.

template<typename ParameterT>
bool get_parameter_or(const std::string &name, ParameterT &parameter, const ParameterT &alternative_value) const

Get the parameter value, or the “alternative_value” if not set, and assign it to “parameter”.

If the parameter was not set, then the “parameter” argument is assigned the “alternative_value”.

Like the version of get_parameter() which returns a bool, this method will not throw the rclcpp::exceptions::ParameterNotDeclaredException exception.

In all cases, the parameter is never set or declared within the node.

Parameters:
  • name[in] The name of the parameter to get.

  • parameter[out] The output where the value of the parameter should be assigned.

  • alternative_value[in] Value to be stored in output if the parameter was not set.

Returns:

true if the parameter was set, false otherwise.

template<typename ParameterT>
ParameterT get_parameter_or(const std::string &name, const ParameterT &alternative_value) const

Return the parameter value, or the “alternative_value” if not set.

If the parameter was not set, then the “alternative_value” argument is returned.

This method will not throw the rclcpp::exceptions::ParameterNotDeclaredException exception.

In all cases, the parameter is never set or declared within the node.

Parameters:
  • name[in] The name of the parameter to get.

  • alternative_value[in] Value to be stored in output if the parameter was not set.

Returns:

The value of the parameter.

std::vector<rclcpp::Parameter> get_parameters(const std::vector<std::string> &names) const

Return the parameters by the given parameter names.

Like get_parameter(const std::string &), this method may throw the rclcpp::exceptions::ParameterNotDeclaredException exception if the requested parameter has not been declared and undeclared parameters are not allowed, and may throw the rclcpp::exceptions::ParameterUninitializedException exception.

Also like get_parameter(const std::string &), if undeclared parameters are allowed and the parameter has not been declared, then the corresponding rclcpp::Parameter will be default initialized and therefore have the type rclcpp::ParameterType::PARAMETER_NOT_SET.

Parameters:

names[in] The names of the parameters to be retrieved.

Throws:
Returns:

The parameters that were retrieved.

template<typename ParameterT>
bool get_parameters(const std::string &prefix, std::map<std::string, ParameterT> &values) const

Get the parameter values for all parameters that have a given prefix.

The “prefix” argument is used to list the parameters which are prefixed with that prefix, see also list_parameters().

The resulting list of parameter names are used to get the values of the parameters.

The names which are used as keys in the values map have the prefix removed. For example, if you use the prefix “foo” and the parameters “foo.ping” and “foo.pong” exist, then the returned map will have the keys “ping” and “pong”.

An empty string for the prefix will match all parameters.

If no parameters with the prefix are found, then the output parameter “values” will be unchanged and false will be returned. Otherwise, the parameter names and values will be stored in the map and true will be returned to indicate “values” was mutated.

This method will never throw the rclcpp::exceptions::ParameterNotDeclaredException exception because the action of listing the parameters is done atomically with getting the values, and therefore they are only listed if already declared and cannot be undeclared before being retrieved.

Like the templated get_parameter() variant, this method will attempt to coerce the parameter values into the type requested by the given template argument, which may fail and throw an exception.

Parameters:
  • prefix[in] The prefix of the parameters to get.

  • values[out] The map used to store the parameter names and values, respectively, with one entry per parameter matching prefix.

Throws:

rclcpp::ParameterTypeException – if the requested type does not match the value of the parameter which is stored.

Returns:

true if output “values” was changed, false otherwise.

rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const

Return the parameter descriptor for the given parameter name.

Like get_parameters(), this method may throw the rclcpp::exceptions::ParameterNotDeclaredException exception if the requested parameter has not been declared and undeclared parameters are not allowed.

If undeclared parameters are allowed, then a default initialized descriptor will be returned.

Parameters:

name[in] The name of the parameter to describe.

Throws:
  • rclcpp::exceptions::ParameterNotDeclaredException – if the parameter has not been declared and undeclared parameters are not allowed.

  • std::runtime_error – if the number of described parameters is more than one

Returns:

The descriptor for the given parameter name.

std::vector<rcl_interfaces::msg::ParameterDescriptor> describe_parameters(const std::vector<std::string> &names) const

Return a vector of parameter descriptors, one for each of the given names.

Like get_parameters(), this method may throw the rclcpp::exceptions::ParameterNotDeclaredException exception if any of the requested parameters have not been declared and undeclared parameters are not allowed.

If undeclared parameters are allowed, then a default initialized descriptor will be returned for the undeclared parameter’s descriptor.

If the names vector is empty, then an empty vector will be returned.

Parameters:

names[in] The list of parameter names to describe.

Throws:
  • rclcpp::exceptions::ParameterNotDeclaredException – if any of the parameters have not been declared and undeclared parameters are not allowed.

  • std::runtime_error – if the number of described parameters is more than one

Returns:

A list of parameter descriptors, one for each parameter given.

std::vector<uint8_t> get_parameter_types(const std::vector<std::string> &names) const

Return a vector of parameter types, one for each of the given names.

Like get_parameters(), this method may throw the rclcpp::exceptions::ParameterNotDeclaredException exception if any of the requested parameters have not been declared and undeclared parameters are not allowed.

If undeclared parameters are allowed, then the default type rclcpp::ParameterType::PARAMETER_NOT_SET will be returned.

Parameters:

names[in] The list of parameter names to get the types.

Throws:

rclcpp::exceptions::ParameterNotDeclaredException – if any of the parameters have not been declared and undeclared parameters are not allowed.

Returns:

A list of parameter types, one for each parameter given.

rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector<std::string> &prefixes, uint64_t depth) const

Return a list of parameters with any of the given prefixes, up to the given depth.

Todo:

: properly document and test this method.

RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback (PreSetParametersCallbackType callback)

Add a callback that gets triggered before parameters are validated.

This callback can be used to modify the original list of parameters being set by the user.

The modified list of parameters is then forwarded to the “on set parameter” callback for validation.

The callback is called whenever any of the set_parameter* methods are called or when a set parameter service request is received.

The callback takes a reference to the vector of parameters to be set.

The vector of parameters may be modified by the callback.

One of the use case of “pre set callback” can be updating additional parameters conditioned on changes to a parameter.

Users should retain a copy of the returned shared pointer, as the callback is valid only as long as the smart pointer is alive.

For an example callback:

void
preSetParameterCallback(std::vector<rclcpp::Parameter> & parameters)
{
 for (auto & param : parameters) {
   if (param.get_name() == "param1") {
     parameters.push_back(rclcpp::Parameter("param2", 4.0));
   }
 }
}
The above callback appends ‘param2’ to the list of parameters to be set if ‘param1’ is being set by the user.

All parameters in the vector will be set atomically.

Note that the callback is only called while setting parameters with set_parameter, set_parameters, set_parameters_atomically, or externally with a parameters service.

The callback is not called when parameters are declared with declare_parameter or declare_parameters.

The callback is not called when parameters are undeclared with undeclare_parameter.

An empty modified parameter list from the callback will result in “set_parameter*” returning an unsuccessful result.

The remove_pre_set_parameters_callback can be used to deregister the callback.

Parameters:

callback – The callback to register.

Throws:

std::bad_alloc – if the allocation of the PreSetParametersCallbackHandle fails.

Returns:

A shared pointer. The callback is valid as long as the smart pointer is alive.

RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback (OnSetParametersCallbackType callback)

Add a callback to validate parameters before they are set.

The callback signature is designed to allow handling of any of the above set_parameter* or declare_parameter* methods, and so it takes a const reference to a vector of parameters to be set, and returns an instance of rcl_interfaces::msg::SetParametersResult to indicate whether or not the parameter should be set or not, and if not why.

Users should retain a copy of the returned shared pointer, as the callback is valid only as long as the smart pointer is alive.

For an example callback:

rcl_interfaces::msg::SetParametersResult
my_callback(const std::vector<rclcpp::Parameter> & parameters)
{
  rcl_interfaces::msg::SetParametersResult result;
  result.successful = true;
  for (const auto & parameter : parameters) {
    if (!some_condition) {
      result.successful = false;
      result.reason = "the reason it could not be allowed";
    }
  }
  return result;
}

You can see that the SetParametersResult is a boolean flag for success and an optional reason that can be used in error reporting when it fails.

This allows the node developer to control which parameters may be changed.

It is considered bad practice to reject changes for “unknown” parameters as this prevents other parts of the node (that may be aware of these parameters) from handling them.

Note that the callback is called when declare_parameter() and its variants are called, and so you cannot assume the parameter has been set before this callback, so when checking a new value against the existing one, you must account for the case where the parameter is not yet set.

The callback is not called when parameters are undeclared with undeclare_parameter.

Some constraints like read_only are enforced before the callback is called.

The callback may introspect other already set parameters (by calling any of the {get,list,describe}_parameter() methods), but may not modify other parameters (by calling any of the {set,declare}_parameter() methods) or modify the registered callback itself (by calling the add_on_set_parameters_callback() method). If a callback tries to do any of the latter things, rclcpp::exceptions::ParameterModifiedInCallbackException will be thrown.

The callback functions must remain valid as long as the returned smart pointer is valid. The returned smart pointer can be promoted to a shared version.

Resetting or letting the smart pointer go out of scope unregisters the callback. remove_on_set_parameters_callback can also be used.

The registered callbacks are called when a parameter is set. When a callback returns a not successful result, the remaining callbacks aren’t called. The order of the callback is the reverse from the registration order.

Parameters:

callback – The callback to register.

Throws:

std::bad_alloc – if the allocation of the OnSetParametersCallbackHandle fails.

Returns:

A shared pointer. The callback is valid as long as the smart pointer is alive.

RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PostSetParametersCallbackHandle::SharedPtr add_post_set_parameters_callback (PostSetParametersCallbackType callback)

Add a callback that gets triggered after parameters are set successfully.

The callback is called when any of the set_parameter* or declare_parameter* methods are successful.

Users should retain a copy of the returned shared pointer, as the callback is valid only as long as the smart pointer is alive.

The callback takes a reference to a const vector of parameters that have been set successfully.

The post callback can be valuable as a place to cause side-effects based on parameter changes. For instance updating internally tracked class attributes once parameters have been changed successfully.

For an example callback:

void
postSetParameterCallback(const std::vector<rclcpp::Parameter> & parameters)
{
 for(const auto & param:parameters) {
  // the internal class member can be changed after
  // successful change to param1 or param2
   if(param.get_name() == "param1") {
     internal_tracked_class_parameter_1_ = param.get_value<double>();
   }
   else if(param.get_name() == "param2") {
     internal_tracked_class_parameter_2_ = param.get_value<double>();
   }
 }
}

The above callback takes a const reference to list of parameters that have been set successfully and as a result of this updates the internally tracked class attributes internal_tracked_class_parameter_1_ and internal_tracked_class_parameter_2_ respectively.

This callback should not modify parameters.

The callback is called when parameters are declared with declare_parameter or declare_parameters. See declare_parameter or declare_parameters above.

The callback is not called when parameters are undeclared with undeclare_parameter.

If you want to make changes to parameters based on changes to another, use add_pre_set_parameters_callback.

The remove_post_set_parameters_callback can be used to deregister the callback.

Parameters:

callback – The callback to register.

Throws:

std::bad_alloc – if the allocation of the OnSetParametersCallbackHandle fails.

Returns:

A shared pointer. The callback is valid as long as the smart pointer is alive.

RCLCPP_PUBLIC void remove_pre_set_parameters_callback (const PreSetParametersCallbackHandle *const handler)

Remove a callback registered with add_pre_set_parameters_callback.

Delete a handler returned by add_pre_set_parameters_callback.

Parameters:

handler – The callback handler to remove.

Throws:

std::runtime_error – if the handler was not created with add_pre_set_parameters_callback, or if it has been removed before.

RCLCPP_PUBLIC void remove_on_set_parameters_callback (const OnSetParametersCallbackHandle *const handler)

Remove a callback registered with add_on_set_parameters_callback.

Delete a handler returned by add_on_set_parameters_callback.

e.g.:

remove_on_set_parameters_callback(scoped_callback.get())

As an alternative, the smart pointer can be reset:

scoped_callback.reset()

Supposing that scoped_callback was the only owner.

Calling remove_on_set_parameters_callback more than once with the same handler, or calling it after the shared pointer has been reset is an error. Resetting or letting the smart pointer go out of scope after calling remove_on_set_parameters_callback is not a problem.

Parameters:

handler – The callback handler to remove.

Throws:

std::runtime_error – if the handler was not created with add_on_set_parameters_callback, or if it has been removed before.

RCLCPP_PUBLIC void remove_post_set_parameters_callback (const PostSetParametersCallbackHandle *const handler)

Remove a callback registered with add_post_set_parameters_callback.

Delete a handler returned by add_post_set_parameters_callback.

Parameters:

handler – The callback handler to remove.

Throws:

std::runtime_error – if the handler was not created with add_post_set_parameters_callback, or if it has been removed before.

RCLCPP_PUBLIC std::vector< std::string > get_node_names () const

Get the fully-qualified names of all available nodes.

The fully-qualified name includes the local namespace and name of the node.

Returns:

A vector of fully-qualified names of nodes.

RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_topic_names_and_types () const

Return a map of existing topic names to list of topic types.

Throws:

std::runtime_error – anything that rcl_error can throw

Returns:

a map of existing topic names to list of topic types.

RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types () const

Return a map of existing service names to list of service types.

Throws:

std::runtime_error – anything that rcl_error can throw

Returns:

a map of existing service names to list of service types.

RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types_by_node (const std::string &node_name, const std::string &namespace_) const

Return a map of existing service names to list of service types for a specific node.

This function only considers services - not clients. The returned names are the actual names used and do not have remap rules applied.

Parameters:
  • node_name[in] name of the node.

  • namespace_[in] namespace of the node.

Throws:

std::runtime_error – anything that rcl_error can throw.

Returns:

a map of existing service names to list of service types.

RCLCPP_PUBLIC size_t count_publishers (const std::string &topic_name) const

Return the number of publishers created for a given topic.

Parameters:

topic_name[in] the actual topic name used; it will not be automatically remapped.

Throws:

std::runtime_error – if publishers could not be counted

Returns:

number of publishers that have been created for the given topic.

RCLCPP_PUBLIC size_t count_subscribers (const std::string &topic_name) const

Return the number of subscribers created for a given topic.

Parameters:

topic_name[in] the actual topic name used; it will not be automatically remapped.

Throws:

std::runtime_error – if subscribers could not be counted

Returns:

number of subscribers that have been created for the given topic.

RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_publishers_info_by_topic (const std::string &topic_name, bool no_mangle=false) const

Return the topic endpoint information about publishers on a given topic.

The returned parameter is a list of topic endpoint information, where each item will contain the node name, node namespace, topic type, endpoint type, topic endpoint’s GID, and its QoS profile.

When the no_mangle parameter is true, the provided topic_name should be a valid topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps). When the no_mangle parameter is false, the provided topic_name should follow ROS topic name conventions.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic will be expanded using this node’s namespace and name. The queried topic_name is not remapped.

Parameters:
  • topic_name[in] the actual topic name used; it will not be automatically remapped.

  • no_mangle[in] if true, topic_name needs to be a valid middleware topic name, otherwise it should be a valid ROS topic name. Defaults to false.

Throws:
  • InvalidTopicNameError – if the given topic_name is invalid.

  • std::runtime_error – if internal error happens.

Returns:

a list of TopicEndpointInfo representing all the publishers on this topic.

RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_subscriptions_info_by_topic (const std::string &topic_name, bool no_mangle=false) const

Return the topic endpoint information about subscriptions on a given topic.

The returned parameter is a list of topic endpoint information, where each item will contain the node name, node namespace, topic type, endpoint type, topic endpoint’s GID, and its QoS profile.

When the no_mangle parameter is true, the provided topic_name should be a valid topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps). When the no_mangle parameter is false, the provided topic_name should follow ROS topic name conventions.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic will be expanded using this node’s namespace and name. The queried topic_name is not remapped.

Parameters:
  • topic_name[in] the actual topic name used; it will not be automatically remapped.

  • no_mangle[in] if true, topic_name needs to be a valid middleware topic name, otherwise it should be a valid ROS topic name. Defaults to false.

Throws:
  • InvalidTopicNameError – if the given topic_name is invalid.

  • std::runtime_error – if internal error happens.

Returns:

a list of TopicEndpointInfo representing all the subscriptions on this topic.

RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event ()

Return a graph event, which will be set anytime a graph change occurs.

RCLCPP_PUBLIC void wait_for_graph_change (rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout)

Wait for a graph event to occur by waiting on an Event to become set.

The given Event must be acquire through the get_graph_event() method.

Parameters:
  • event[in] pointer to an Event to wait for

  • timeout[in] nanoseconds to wait for the Event to change the state

Throws:
  • InvalidEventError – if the given event is nullptr

  • EventNotRegisteredError – if the given event was not acquired with get_graph_event().

RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock ()

Get a clock as a non-const shared pointer which is managed by the node.

RCLCPP_PUBLIC rclcpp::Clock::ConstSharedPtr get_clock () const

Get a clock as a const shared pointer which is managed by the node.

RCLCPP_PUBLIC Time now () const

Returns current time from the time source specified by clock_type.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()

Return the Node’s internal NodeBaseInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface ()

Return the Node’s internal NodeClockInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface ()

Return the Node’s internal NodeGraphInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface ()

Return the Node’s internal NodeLoggingInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface ()

Return the Node’s internal NodeTimersInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface ()

Return the Node’s internal NodeTopicsInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface ()

Return the Node’s internal NodeServicesInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface ()

Return the Node’s internal NodeWaitablesInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface ()

Return the Node’s internal NodeParametersInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface ()

Return the Node’s internal NodeTimeSourceInterface implementation.

RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface ()

Return the Node’s internal NodeTypeDescriptionsInterface implementation.

RCLCPP_PUBLIC const std::string & get_sub_namespace () const

Return the sub-namespace, if this is a sub-node, otherwise an empty string.

The returned sub-namespace is either the accumulated sub-namespaces which were given to one-to-many create_sub_node() calls, or an empty string if this is an original node instance, i.e. not a sub-node.

For example, consider:

auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
node->get_sub_namespace();  // -> ""
auto sub_node1 = node->create_sub_node("a");
sub_node1->get_sub_namespace();  // -> "a"
auto sub_node2 = sub_node1->create_sub_node("b");
sub_node2->get_sub_namespace();  // -> "a/b"
auto sub_node3 = node->create_sub_node("foo");
sub_node3->get_sub_namespace();  // -> "foo"
node->get_sub_namespace();  // -> ""

get_namespace() will return the original node namespace, and will not include the sub-namespace if one exists. To get that you need to call the get_effective_namespace() method.

See also

get_namespace()

Returns:

the sub-namespace string, not including the node’s original namespace

RCLCPP_PUBLIC const std::string & get_effective_namespace () const

Return the effective namespace that is used when creating entities.

The returned namespace is a concatenation of the node namespace and the accumulated sub-namespaces, which is used as the namespace when creating entities which have relative names.

For example, consider:

auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
node->get_effective_namespace();  // -> "/my_ns"
auto sub_node1 = node->create_sub_node("a");
sub_node1->get_effective_namespace();  // -> "/my_ns/a"
auto sub_node2 = sub_node1->create_sub_node("b");
sub_node2->get_effective_namespace();  // -> "/my_ns/a/b"
auto sub_node3 = node->create_sub_node("foo");
sub_node3->get_effective_namespace();  // -> "/my_ns/foo"
node->get_effective_namespace();  // -> "/my_ns"

See also

get_namespace()

Returns:

the sub-namespace string, not including the node’s original namespace

RCLCPP_PUBLIC rclcpp::Node::SharedPtr create_sub_node (const std::string &sub_namespace)

Create a sub-node, which will extend the namespace of all entities created with it.

A sub-node (short for subordinate node) is an instance of this class which has been created using an existing instance of this class, but which has an additional sub-namespace (short for subordinate namespace) associated with it. The sub-namespace will extend the node’s namespace for the purpose of creating additional entities, such as Publishers, Subscriptions, Service Clients and Servers, and so on.

By default, when an instance of this class is created using one of the public constructors, it has no sub-namespace associated with it, and therefore is not a sub-node. That “normal” node instance may, however, be used to create further instances of this class, based on the original instance, which have an additional sub-namespace associated with them. This may be done by using this method, create_sub_node().

Furthermore, a sub-node may be used to create additional sub-node’s, in which case the sub-namespace passed to this function will further extend the sub-namespace of the existing sub-node. See get_sub_namespace() and get_effective_namespace() for examples.

Note that entities which use absolute names are not affected by any namespaces, neither the normal node namespace nor any sub-namespace. Note also that the fully qualified node name is unaffected by a sub-namespace.

The sub-namespace should be relative, and an exception will be thrown if the sub-namespace is absolute, i.e. if it starts with a leading ‘/’.

Parameters:

sub_namespace[in] sub-namespace of the sub-node.

Throws:

NameValidationError – if the sub-namespace is absolute, i.e. starts with a leading ‘/’.

Returns:

newly created sub-node

RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options () const

Return the NodeOptions used when creating this node.

template<typename ServiceT>
Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos, rclcpp::CallbackGroup::SharedPtr group)
template<typename ServiceT>
Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group)

Protected Functions

RCLCPP_PUBLIC Node(const Node &other, const std::string &sub_namespace)

Construct a sub-node, which will extend the namespace of all entities created with it.

Parameters:
  • other[in] The node from which a new sub-node is created.

  • sub_namespace[in] The sub-namespace of the sub-node.