Skip to content

Commit cad665e

Browse files
Added extra documentation and clarifications. (#651)
* Added extra documentation and clarifications. Signed-off-by: Johan Rutgeerts <[email protected]> Co-authored-by: Chris Lalancette <[email protected]>
1 parent 2827ae6 commit cad665e

File tree

1 file changed

+80
-36
lines changed

1 file changed

+80
-36
lines changed

demo_nodes_cpp/src/parameters/set_parameters_callback.cpp

Lines changed: 80 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// limitations under the License.
1414

1515
/**
16-
* Example usage: changing param1 successfully will result in setting of param2.
17-
* ros2 service call /set_parameters_callback/set_parameters rcl_interfaces/srv/SetParameters
16+
* Example usage: changing 'param1' successfully will result in setting of 'param2'.
17+
* ros2 service call /set_param_callback_node/set_parameters rcl_interfaces/srv/SetParameters
1818
"{parameters: [{name: "param1", value: {type: 3, double_value: 1.0}}]}"
1919
*/
2020

@@ -27,7 +27,7 @@
2727
#include "demo_nodes_cpp/visibility_control.h"
2828

2929
/**
30-
* node for demonstrating correct usage of pre_set, on_set
30+
* This example node demonstrates the usage of pre_set, on_set
3131
* and post_set parameter callbacks
3232
*/
3333
namespace demo_nodes_cpp
@@ -37,44 +37,62 @@ class SetParametersCallback : public rclcpp::Node
3737
public:
3838
DEMO_NODES_CPP_PUBLIC
3939
explicit SetParametersCallback(const rclcpp::NodeOptions & options)
40-
: Node("set_parameters_callback", options)
40+
: Node("set_param_callback_node", options)
4141
{
42-
// tracks "param1" value
43-
internal_tracked_class_parameter_1_ = this->declare_parameter("param1", 0.0);
44-
// tracks "param2" value
45-
internal_tracked_class_parameter_2_ = this->declare_parameter("param2", 0.0);
46-
47-
// setting another parameter from the callback is possible
48-
// we expect the callback to be called for param2
49-
auto pre_set_parameter_callback =
42+
// Declare a parameter named "param1" in this node, with default value 1.0:
43+
this->declare_parameter("param1", 1.0);
44+
// Retrieve the value of 'param1' into a member variable 'value_1_'.
45+
value_1_ = this->get_parameter("param1").as_double();
46+
47+
// Following statement does the same for 'param2' and 'value_2_', but in a more concise way:
48+
value_2_ = this->declare_parameter("param2", 2.0);
49+
50+
// Define a callback function that will be registered as the 'pre_set_parameters_callback':
51+
// This callback is passed the list of the Parameter objects that are intended to be changed,
52+
// and returns nothing.
53+
// Through this callback it is possible to modify the upcoming changes by changing,
54+
// adding or removing entries of the Parameter list.
55+
//
56+
// This callback should not change the state of the node (i.e. in this example
57+
// the callback should not change 'value_1_' and 'value_2_').
58+
//
59+
auto modify_upcoming_parameters_callback =
5060
[](std::vector<rclcpp::Parameter> & parameters) {
61+
// As an example: whenever "param1" is changed, "param2" is set to 4.0:
5162
for (auto & param : parameters) {
52-
// if "param1" is being set try setting "param2" as well.
5363
if (param.get_name() == "param1") {
5464
parameters.push_back(rclcpp::Parameter("param2", 4.0));
5565
}
5666
}
5767
};
5868

59-
// validation callback
60-
auto on_set_parameter_callback =
69+
70+
// Define a callback function that will be registered as the 'on_set_parameters_callback':
71+
// The purpose of this callback is to allow the node to inspect the upcoming change
72+
// to the parameters and explicitly approve or reject the change.
73+
// If the change is rejected, no parameters are changed.
74+
//
75+
// This callback should not change the state of the node (i.e. in this example
76+
// the callback should not change 'value_1_' and 'value_2_').
77+
//
78+
auto validate_upcoming_parameters_callback =
6179
[](std::vector<rclcpp::Parameter> parameters) {
6280
rcl_interfaces::msg::SetParametersResult result;
6381
result.successful = true;
6482

6583
for (const auto & param : parameters) {
84+
// As an example: no parameters are changed if a value > 5.0 is specified for 'param1',
85+
// or a value < -5.0 for 'param2'.
6686
if (param.get_name() == "param1") {
67-
// Arbitrarily reject updates setting param1 > 5.0
6887
if (param.get_value<double>() > 5.0) {
6988
result.successful = false;
70-
result.reason = "cannot set param1 > 5.0";
89+
result.reason = "cannot set 'param1' > 5.0";
7190
break;
7291
}
7392
} else if (param.get_name() == "param2") {
74-
// Arbitrarily reject updates setting param2 < -5.0
7593
if (param.get_value<double>() < -5.0) {
7694
result.successful = false;
77-
result.reason = "cannot set param2 < -5.0";
95+
result.reason = "cannot set 'param2' < -5.0";
7896
break;
7997
}
8098
}
@@ -83,36 +101,62 @@ class SetParametersCallback : public rclcpp::Node
83101
return result;
84102
};
85103

86-
// can change internally tracked class attributes
87-
auto post_set_parameter_callback =
104+
// Define a callback function that will be registered as the 'post_set_parameters_callback':
105+
// This callback is passed a list of immutable Parameter objects, and returns nothing.
106+
// The purpose of this callback is to react to changes from parameters
107+
// that have successfully been accepted.
108+
//
109+
// This callback can change the internal state of the node. E.g.:
110+
// - In this example the callback updates the local copies 'value_1_' and 'value_2_',
111+
// - Another example could be to trigger recalculation of a kinematic model due to
112+
// the change of link length parameters,
113+
// - Yet another example could be to emit a signal for an HMI update,
114+
// - Etc.
115+
//
116+
auto react_to_updated_parameters_callback =
88117
[this](const std::vector<rclcpp::Parameter> & parameters) {
89118
for (const auto & param : parameters) {
90119
if (param.get_name() == "param1") {
91-
internal_tracked_class_parameter_1_ = param.get_value<double>();
120+
value_1_ = param.get_value<double>();
121+
RCLCPP_INFO(get_logger(), "Member variable 'value_1_' set to: %f.", value_1_);
92122
}
93-
94-
// the class member can be changed after successful set to param2.
95123
if (param.get_name() == "param2") {
96-
internal_tracked_class_parameter_2_ = param.get_value<double>();
124+
value_2_ = param.get_value<double>();
125+
RCLCPP_INFO(get_logger(), "Member variable 'value_2_' set to: %f.", value_2_);
97126
}
98127
}
99128
};
100129

130+
131+
// Register the callbacks:
132+
// In this example all three callbacks are registered, but this is not mandatory
133+
// The handles (i.e. the returned shared pointers) must be kept, as the callback
134+
// is only registered as long as the shared pointer is alive.
101135
pre_set_parameters_callback_handle_ = this->add_pre_set_parameters_callback(
102-
pre_set_parameter_callback);
136+
modify_upcoming_parameters_callback);
103137
on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(
104-
on_set_parameter_callback);
138+
validate_upcoming_parameters_callback);
105139
post_set_parameters_callback_handle_ = this->add_post_set_parameters_callback(
106-
post_set_parameter_callback);
140+
react_to_updated_parameters_callback);
107141

108-
RCLCPP_INFO(get_logger(), "This node shows off parameter callbacks.");
109-
RCLCPP_INFO(get_logger(), "To do that, it exhibits the following behavior:");
142+
143+
// Output some info:
144+
RCLCPP_INFO(get_logger(), "This node demonstrates the use of parameter callbacks.");
145+
RCLCPP_INFO(get_logger(), "As an example, it exhibits the following behavior:");
146+
RCLCPP_INFO(
147+
get_logger(),
148+
" * Two parameters of type double are declared in the node: 'param1' and 'param2'");
149+
RCLCPP_INFO(get_logger(), " * 'param1' cannot be set to a value > 5.0");
150+
RCLCPP_INFO(get_logger(), " * 'param2' cannot be set to a value < -5.0");
151+
RCLCPP_INFO(get_logger(), " * Each time 'param1' is set, 'param2' is automatically set to 4.0");
110152
RCLCPP_INFO(
111153
get_logger(),
112-
" * Two parameters of type double are declared on the node, param1 and param2");
113-
RCLCPP_INFO(get_logger(), " * param1 cannot be set to a value > 5.0");
114-
RCLCPP_INFO(get_logger(), " * param2 cannot be set to a value < -5.0");
115-
RCLCPP_INFO(get_logger(), " * any time param1 is set, param2 is automatically set to 4.0");
154+
" * Member variables 'value_1_' and 'value_2_' are updated upon change of the parameters.");
155+
RCLCPP_INFO(get_logger(), "To try it out set a parameter, e.g.:");
156+
RCLCPP_INFO(get_logger(), " ros2 param set set_param_callback_node param1 10.0");
157+
RCLCPP_INFO(get_logger(), " ros2 param set set_param_callback_node param1 3.0");
158+
RCLCPP_INFO(get_logger(), "The first command will fail.");
159+
RCLCPP_INFO(get_logger(), "The 2nd command will set 'param1' to 3.0 and 'param2' to 4.0.");
116160
}
117161

118162
private:
@@ -123,8 +167,8 @@ class SetParametersCallback : public rclcpp::Node
123167
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr
124168
post_set_parameters_callback_handle_;
125169

126-
double internal_tracked_class_parameter_1_;
127-
double internal_tracked_class_parameter_2_;
170+
double value_1_;
171+
double value_2_;
128172
};
129173

130174
} // namespace demo_nodes_cpp

0 commit comments

Comments
 (0)