-
Notifications
You must be signed in to change notification settings - Fork 522
Description
Feature Request
Feature Description
Currently the rclcpp::Node::add_on_set_parameter_callback() only support callback of rcl_interfaces::msg::SetParametersResult callback(const std::vector<rclcpp::Parameter> ¶meters). As explained in the add_on_set_parameters_callback() documentation:
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.
The problem with const reference is we cannot modify the value of the parameters to be set inside the on set parameter callback. And the bad things, we also couldn't call set_parameter() inside the callback as stated in the documentation
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.
And by seeing the example in the documentation, we could conclude that the on set parameter callback could only filter an invalid parameter by rejecting it.
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;
}And why would someone want to modify the parameters during on set parameter callback? Considered the following scenario, i have a parameter that should only accept the double value of 0.0 to 100.0. if i set the parameter with double value between 0.0 to 100.0, then it would be fine. but what if i accidently set the parameter to be 101.0, using the current on_set_parameter_callback() behavior, then i could only reject it. wouldn't it be better if i could accept it in condition that the parameter value is clamped to 100.0? or what if i accidently set the parameter using an integer value of 50? when i accept it, the parameter would simply changed from double to integer, and it would be considered bad. But i shouldn't reject it either. Wouldn't it be better if i could accept it in condition that the parameter type to be casted to double value?.
Implementation Considerations
Add a new callback type for rclcpp::Node::add_on_set_parameter_callback() with the type of rcl_interfaces::msg::SetParametersResult callback(std::vector<rclcpp::Parameter> ¶meters).
For note, I'm already tried to solve the problem with const casting the parameters to std::vector<rclcpp::Parameter> &. It worked, but kinda be a tricky solution and a bad habit as the parameters was implicitly stated to be constant.