Skip to content

Commit

Permalink
Merge pull request #5 from mjeronimo/mjeronimo/add-block-comment
Browse files Browse the repository at this point in the history
A couple more doc fixes from review comments
  • Loading branch information
bpwilcox authored Mar 4, 2021
2 parents a4f5533 + cbc8989 commit f011c3d
Showing 1 changed file with 22 additions and 16 deletions.
38 changes: 22 additions & 16 deletions rclcpp/include/rclcpp/parameter_event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,19 +59,21 @@ struct ParameterEventCallbackHandle
/// 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.
* 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 instance a ParameterEventHandler, providing a ROS node to use
* to create any required subscriptions.
* 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\"",
* 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());
Expand All @@ -80,15 +82,16 @@ struct ParameterEventCallbackHandle
*
* 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.
* 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\"",
* 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());
Expand All @@ -104,15 +107,16 @@ struct ParameterEventCallbackHandle
*
* 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,
* 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::SharedPtr & event) {
* // Look for any updates to parameters in "/a_namespace" as well as any parameter changes
* // to our own node ("this_node").
* // 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
Expand All @@ -122,7 +126,8 @@ struct ParameterEventCallbackHandle
* *event, p, remote_param_name, fqn))
* {
* RCLCPP_INFO(
* node->get_logger(), "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* 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());
Expand All @@ -133,7 +138,8 @@ struct ParameterEventCallbackHandle
* 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\"",
* 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());
Expand All @@ -145,7 +151,7 @@ struct ParameterEventCallbackHandle
* 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
* To remove a parameter event callback, use:
*
* param_handler->remove_event_parameter_callback(handle);
*/
Expand Down

0 comments on commit f011c3d

Please sign in to comment.