@@ -67,19 +67,23 @@ struct ParameterEventCallbackHandle
67
67
* The first step is to instantiate a ParameterEventHandler, providing a ROS node to use
68
68
* to create any required subscriptions:
69
69
*
70
- * auto param_handler = std::make_shared<rclcpp::ParameterEventHandler>(node);
70
+ * ```cpp
71
+ * auto param_handler = std::make_shared<rclcpp::ParameterEventHandler>(node);
72
+ * ```
71
73
*
72
74
* Next, you can supply a callback to the add_parameter_callback method, as follows:
73
75
*
74
- * auto cb1 = [&node](const rclcpp::Parameter & p) {
75
- * RCLCPP_INFO(
76
- * node->get_logger(),
77
- * "cb1: Received an update to parameter \"%s\" of type %s: \"%ld\"",
78
- * p.get_name().c_str(),
79
- * p.get_type_name().c_str(),
80
- * p.as_int());
81
- * };
82
- * auto handle1 = param_handler->add_parameter_callback("an_int_param", cb1);
76
+ * ```cpp
77
+ * auto cb1 = [&node](const rclcpp::Parameter & p) {
78
+ * RCLCPP_INFO(
79
+ * node->get_logger(),
80
+ * "cb1: Received an update to parameter \"%s\" of type %s: \"%ld\"",
81
+ * p.get_name().c_str(),
82
+ * p.get_type_name().c_str(),
83
+ * p.as_int());
84
+ * };
85
+ * auto handle1 = param_handler->add_parameter_callback("an_int_param", cb1);
86
+ * ```
83
87
*
84
88
* In this case, we didn't supply a node name (the third, optional, parameter) so the
85
89
* default will be to monitor for changes to the "an_int_param" parameter associated with
@@ -92,65 +96,71 @@ struct ParameterEventCallbackHandle
92
96
* You may also monitor for changes to parameters in other nodes by supplying the node
93
97
* name to add_parameter_callback:
94
98
*
95
- * auto cb2 = [&node](const rclcpp::Parameter & p) {
96
- * RCLCPP_INFO(
97
- * node->get_logger(),
98
- * "cb2: Received an update to parameter \"%s\" of type: %s: \"%s\"",
99
- * p.get_name().c_str(),
100
- * p.get_type_name().c_str(),
101
- * p.as_string().c_str());
102
- * };
103
- * auto handle2 = param_handler->add_parameter_callback(
104
- * "some_remote_param_name", cb2, "some_remote_node_name");
99
+ * ```cpp
100
+ * auto cb2 = [&node](const rclcpp::Parameter & p) {
101
+ * RCLCPP_INFO(
102
+ * node->get_logger(),
103
+ * "cb2: Received an update to parameter \"%s\" of type: %s: \"%s\"",
104
+ * p.get_name().c_str(),
105
+ * p.get_type_name().c_str(),
106
+ * p.as_string().c_str());
107
+ * };
108
+ * auto handle2 = param_handler->add_parameter_callback(
109
+ * "some_remote_param_name", cb2, "some_remote_node_name");
110
+ * ```
105
111
*
106
112
* In this case, the callback will be invoked whenever "some_remote_param_name" changes
107
113
* on remote node "some_remote_node_name".
108
114
*
109
115
* To remove a parameter callback, reset the callback handle smart pointer or call
110
116
* remove_parameter_callback, passing the handle returned from add_parameter_callback:
111
117
*
112
- * param_handler->remove_parameter_callback(handle2);
118
+ * ```cpp
119
+ * param_handler->remove_parameter_callback(handle2);
120
+ * ```
113
121
*
114
122
* You can also monitor for *all* parameter changes, using add_parameter_event_callback.
115
123
* In this case, the callback will be invoked whenever any parameter changes in the system.
116
124
* You are likely interested in a subset of these parameter changes, so in the callback it
117
125
* is convenient to use a regular expression on the node names or namespaces of interest.
118
126
* For example:
119
127
*
120
- * auto cb3 =
121
- * [fqn, remote_param_name, &node](const rcl_interfaces::msg::ParameterEvent & event) {
122
- * // Look for any updates to parameters in "/a_namespace" as well as any parameter changes
123
- * // to our own node ("this_node")
124
- * std::regex re("(/a_namespace/.*)|(/this_node)");
125
- * if (regex_match(event.node, re)) {
126
- * // Now that we know the event matches the regular expression we scanned for, we can
127
- * // use 'get_parameter_from_event' to get a specific parameter name that we're looking for
128
- * rclcpp::Parameter p;
129
- * if (rclcpp::ParameterEventHandler::get_parameter_from_event(
130
- * event, p, remote_param_name, fqn))
131
- * {
132
- * RCLCPP_INFO(
133
- * node->get_logger(),
134
- * "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
135
- * p.get_name().c_str(),
136
- * p.get_type_name().c_str(),
137
- * p.as_string().c_str());
138
- * }
128
+ * ```cpp
129
+ * auto cb3 =
130
+ * [fqn, remote_param_name, &node](const rcl_interfaces::msg::ParameterEvent & event) {
131
+ * // Look for any updates to parameters in "/a_namespace" as well as any parameter changes
132
+ * // to our own node ("this_node")
133
+ * std::regex re("(/a_namespace/.*)|(/this_node)");
134
+ * if (regex_match(event.node, re)) {
135
+ * // Now that we know the event matches the regular expression we scanned for, we can
136
+ * // use 'get_parameter_from_event' to get a specific parameter name that we're looking for
137
+ * rclcpp::Parameter p;
138
+ * if (rclcpp::ParameterEventHandler::get_parameter_from_event(
139
+ * event, p, remote_param_name, fqn))
140
+ * {
141
+ * RCLCPP_INFO(
142
+ * node->get_logger(),
143
+ * "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
144
+ * p.get_name().c_str(),
145
+ * p.get_type_name().c_str(),
146
+ * p.as_string().c_str());
147
+ * }
139
148
*
140
- * // You can also use 'get_parameter*s*_from_event' to enumerate all changes that came
141
- * // in on this event
142
- * auto params = rclcpp::ParameterEventHandler::get_parameters_from_event(event);
143
- * for (auto & p : params) {
144
- * RCLCPP_INFO(
145
- * node->get_logger(),
146
- * "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
147
- * p.get_name().c_str(),
148
- * p.get_type_name().c_str(),
149
- * p.value_to_string().c_str());
150
- * }
149
+ * // You can also use 'get_parameter*s*_from_event' to enumerate all changes that came
150
+ * // in on this event
151
+ * auto params = rclcpp::ParameterEventHandler::get_parameters_from_event(event);
152
+ * for (auto & p : params) {
153
+ * RCLCPP_INFO(
154
+ * node->get_logger(),
155
+ * "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
156
+ * p.get_name().c_str(),
157
+ * p.get_type_name().c_str(),
158
+ * p.value_to_string().c_str());
151
159
* }
152
- * };
153
- * auto handle3 = param_handler->add_parameter_event_callback(cb3);
160
+ * }
161
+ * };
162
+ * auto handle3 = param_handler->add_parameter_event_callback(cb3);
163
+ * ```
154
164
*
155
165
* For both parameter callbacks and parameter event callbacks, when multiple callbacks are added,
156
166
* the callbacks are invoked last-in, first-called order (LIFO).
@@ -160,7 +170,9 @@ struct ParameterEventCallbackHandle
160
170
*
161
171
* To remove a parameter event callback, reset the callback smart pointer or use:
162
172
*
163
- * param_handler->remove_event_parameter_callback(handle3);
173
+ * ```cpp
174
+ * param_handler->remove_event_parameter_callback(handle3);
175
+ * ```
164
176
*/
165
177
class ParameterEventHandler
166
178
{
0 commit comments