Class ParameterEventHandler

Nested Relationships

Nested Types

Class Documentation

class ParameterEventHandler

A class used to “handle” (monitor and respond to) changes to parameters.

The ParameterEventHandler class allows for the monitoring of changes to node parameters, either a node’s own parameters or parameters owned by other nodes in the system. Multiple parameter callbacks can be set and will be invoked when the specified parameter changes.

The first step is to instantiate a ParameterEventHandler, providing a ROS node to use to create any required subscriptions:

auto param_handler = std::make_shared<rclcpp::ParameterEventHandler>(node);

Next, you can supply a callback to the add_parameter_callback method, as follows:

auto cb1 = [&node](const rclcpp::Parameter & p) { RCLCPP_INFO( node->get_logger(), “cb1: Received an update to parameter "s” of type s: “ld””, p.get_name().c_str(), p.get_type_name().c_str(), p.as_int()); }; auto handle1 = param_handler->add_parameter_callback(“an_int_param”, cb1);

In this case, we didn’t supply a node name (the third, optional, parameter) so the default will be to monitor for changes to the “an_int_param” parameter associated with the ROS node supplied in the ParameterEventHandler constructor. The callback, a lambda function in this case, simply prints out the value of the parameter.

You may also monitor for changes to parameters in other nodes by supplying the node name to add_parameter_callback:

auto cb2 = [&node](const rclcpp::Parameter & p) { RCLCPP_INFO( node->get_logger(), “cb2: Received an update to parameter "s” of type: s: “s””, p.get_name().c_str(), p.get_type_name().c_str(), p.as_string().c_str()); }; auto handle2 = param_handler->add_parameter_callback( “some_remote_param_name”, cb2, “some_remote_node_name”);

In this case, the callback will be invoked whenever “some_remote_param_name” changes on remote node “some_remote_node_name”.

To remove a parameter callback, call remove_parameter_callback, passing the handle returned from add_parameter_callback:

param_handler->remove_parameter_callback(handle2);

You can also monitor for all parameter changes, using add_parameter_event_callback. In this case, the callback will be invoked whenever any parameter changes in the system. You are likely interested in a subset of these parameter changes, so in the callback it is convenient to use a regular expression on the node names or namespaces of interest. For example:

auto cb3 = [fqn, remote_param_name, &node](const rcl_interfaces::msg::ParameterEvent & event) { // Look for any updates to parameters in “/a_namespace” as well as any parameter changes // to our own node (“this_node”) std::regex re(“(/a_namespace/.*)|(/this_node)”); if (regex_match(event.node, re)) { // Now that we know the event matches the regular expression we scanned for, we can // use ‘get_parameter_from_event’ to get a specific parameter name that we’re looking for rclcpp::Parameter p; if (rclcpp::ParameterEventsSubscriber::get_parameter_from_event( event, p, remote_param_name, fqn)) { RCLCPP_INFO( node->get_logger(), “cb3: Received an update to parameter "s” of type: s: “s””, p.get_name().c_str(), p.get_type_name().c_str(), p.as_string().c_str()); }

// You can also use ‘get_parameter*s*_from_event’ to enumerate all changes that came // in on this event auto params = rclcpp::ParameterEventsSubscriber::get_parameters_from_event(event); for (auto & p : params) { RCLCPP_INFO( node->get_logger(), “cb3: Received an update to parameter "s” of type: s: “s””, p.get_name().c_str(), p.get_type_name().c_str(), p.value_to_string().c_str()); } } }; auto handle3 = param_handler->add_parameter_event_callback(cb3);

For both parameter callbacks and parameter event callbacks, when multiple callbacks are added, the callbacks are invoked last-in, first-called order (LIFO).

To remove a parameter event callback, use:

param_handler->remove_event_parameter_callback(handle);

Public Types

using ParameterEventCallbackType = ParameterEventCallbackHandle::ParameterEventCallbackType
using ParameterCallbackType = ParameterCallbackHandle::ParameterCallbackType
using CallbacksContainerType = std::list<ParameterCallbackHandle::WeakPtr>

Public Functions

template<typename NodeT>
inline explicit ParameterEventHandler(NodeT node, const rclcpp::QoS &qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)))

Construct a parameter events monitor.

Parameters:
  • node[in] The node to use to create any required subscribers.

  • qos[in] The QoS settings to use for any subscriptions.

ParameterEventCallbackHandle::SharedPtr add_parameter_event_callback(ParameterEventCallbackType callback)

Set a callback for all parameter events.

This function may be called multiple times to set multiple parameter event callbacks.

Parameters:

callback[in] Function callback to be invoked on parameter updates.

Returns:

A handle used to refer to the callback.

void remove_parameter_event_callback(ParameterEventCallbackHandle::SharedPtr callback_handle)

Remove parameter event callback registered with add_parameter_event_callback.

Parameters:

callback_handle[in] Handle of the callback to remove.

ParameterCallbackHandle::SharedPtr add_parameter_callback(const std::string &parameter_name, ParameterCallbackType callback, const std::string &node_name = "")

Add a callback for a specified parameter.

If a node_name is not provided, defaults to the current node.

Parameters:
  • parameter_name[in] Name of parameter to monitor.

  • callback[in] Function callback to be invoked upon parameter update.

  • node_name[in] Name of node which hosts the parameter.

Returns:

A handle used to refer to the callback.

void remove_parameter_callback(ParameterCallbackHandle::SharedPtr callback_handle)

Remove a parameter callback registered with add_parameter_callback.

The parameter name and node name are inspected from the callback handle. The callback handle is erased from the list of callback handles on the {parameter_name, node_name} in the map. An error is thrown if the handle does not exist and/or was already removed.

Parameters:

callback_handle[in] Handle of the callback to remove.

Public Static Functions

static bool get_parameter_from_event(const rcl_interfaces::msg::ParameterEvent &event, rclcpp::Parameter &parameter, const std::string &parameter_name, const std::string &node_name = "")

Get an rclcpp::Parameter from a parameter event.

If a node_name is not provided, defaults to the current node.

Parameters:
  • event[in] Event msg to be inspected.

  • parameter[out] Reference to rclcpp::Parameter to be assigned.

  • parameter_name[in] Name of parameter.

  • node_name[in] Name of node which hosts the parameter.

Returns:

Output parameter is set with requested parameter info and returns true if requested parameter name and node is in event. Otherwise, returns false.

static rclcpp::Parameter get_parameter_from_event(const rcl_interfaces::msg::ParameterEvent &event, const std::string &parameter_name, const std::string &node_name = "")

Get an rclcpp::Parameter from parameter event.

If a node_name is not provided, defaults to the current node.

The user is responsible to check if the returned parameter has been properly assigned. By default, if the requested parameter is not found in the event, the returned parameter has parameter value of type rclcpp::PARAMETER_NOT_SET.

Parameters:
  • event[in] Event msg to be inspected.

  • parameter_name[in] Name of parameter.

  • node_name[in] Name of node which hosts the parameter.

Returns:

The resultant rclcpp::Parameter from the event.

static std::vector<rclcpp::Parameter> get_parameters_from_event(const rcl_interfaces::msg::ParameterEvent &event)

Get all rclcpp::Parameter values from a parameter event.

Parameters:

event[in] Event msg to be inspected.

Returns:

A vector rclcpp::Parameter values from the event.

Protected Functions

std::string resolve_path(const std::string &path)

Protected Attributes

std::shared_ptr<Callbacks> callbacks_
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr event_subscription_
struct Callbacks

Public Functions

void event_callback(const rcl_interfaces::msg::ParameterEvent &event)

Callback for parameter events subscriptions.

Public Members

std::recursive_mutex mutex_
std::unordered_map<std::pair<std::string, std::string>, CallbacksContainerType, StringPairHash> parameter_callbacks_
std::list<ParameterEventCallbackHandle::WeakPtr> event_callbacks_
class StringPairHash

Public Functions

template<typename T>
inline void hash_combine(std::size_t &seed, const T &v) const
inline size_t operator()(const std::pair<std::string, std::string> &s) const