Open squizz617 opened 2 years ago
after all, i am not really convinced that these are the problems...
(rcl & rmw) req handled -> param callback invoked, en/disables ROS time, and returns SetParametersResult instead of being subscribe to /parameter_events -> (rcl & rmw) req handled -> param callback invoked and returns SetParametersResult -> new param published to /parameter_events -> on_parameter_event callback invoked and en/disables ROS time ?
as far as i can see, those look pretty different. i believe we should not (can not) assume the result when it is being set.
Error checking code in TimeSource::on_parameter_event() is not reachable.
for me, can not be reachable for specific sequence
does not mean redundant
in this case, because function scope is different. i think we should keep this check for each function scope.
(rcl & rmw) req handled -> param callback invoked, en/disables ROS time, and returns SetParametersResult instead of being
subscribe to
/parameter_events
-> (rcl & rmw) req handled -> param callback invoked and returns SetParametersResult -> new param published to/parameter_events
->on_parameter_event
callback invoked and en/disables ROS time ?
So its tricky, but that isn't the intended use of the callbacks registered to add_on_set_parameters_callback
. In particular, the callback that is registered through add_on_set_parameters_callback
should have no side-effects; it should really only verify whether the parameters that are going to be set are valid, and return successful or not.
To understand why that is, it helps to think about the fact that add_on_set_parameters_callback
puts the callback in a chain of callbacks. All of the callbacks are called, one after the other, when parameters are set. If any of them returns an error, the call to set_parameter
fails and no parameters are changed.
To further illustrate the problem, consider this (contrived) code:
MyNode::MyNode()
{
cb1 = add_on_set_parameters_callback[this](const std::vector<rclcpp::Parameter> & parameters) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const auto & parameter : parameters) {
if (parameter.get_name() == "foo") {
this->side_effect = 25;
}
}
return result;
});
cb2 = add_on_set_parameters_callback[this](const std::vector<rclcpp::Parameter> & parameters) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const auto & parameter : parameters) {
if (parameter.get_name() == "bar") {
result.successful = false;
}
}
return result;
});
}
In this case, if set_parameters
is called with foo
, then we'll set the member variable to 25, and that is all that will happen. But if set_parameters
is called with foo
and bar
, then the member variable will be set to 25, but the set parameter call as a whole will fail. So now you are in a situation where you've caused some side-effect to happen in the class, but the parameter was not set as you expect.
The above example is obviously contrived; you would never do this in a single node. But since a common pattern is to pass nodes around and reuse them, there definitely could be other pieces of code that add their own parameter callbacks into the chain.
Hi. I was cross-checking ros2 client libraries for API consistency, and came across these issues that needs fixing in my opinion.
When an
rclcpp::Node
object is created, a subscription is created, whilerclpy.Node
does not create one./parameter_events
is created viarclcpp::AsyncParametersClient::on_parameter_event
, bindingTimeSource::on_parameter_event
callback to the/parameter_events
topic (src).use_sim_time
parameter is set, e.g., throughros2 param set /node_name use_sim_time True
, parameter service handles it by taking the request, setting the parameter, and publishing to/parameter_events
. As a message is published to/parameter_events
,TimeSource::on_parameter_event
callback is invoked.TimeSource::on_parameter_event
checks if the event belongs to the node and isuse_sim_time
, verifies the type, and enables or disables ROS time according to the parameter value.on_parameter_event
cannot just be a part of the inline function that's registered as a parameter callback here. Doesn'tsim_time_cb_handler_
exist specifically for this purpose?set param
request be as simple as/parameter_events
-> (rcl & rmw) req handled -> param callback invoked and returns SetParametersResult -> new param published to/parameter_events
->on_parameter_event
callback invoked and en/disables ROS time ?Error checking code in
TimeSource::on_parameter_event()
is not reachable.use_sim_time
, anduse_sim_time
with wrong types (i.e., other than bool) are rejected by the handler./parameter_events
as param set is not successful, andTimeSource::on_parameter_event
callback is not invoked.TimeSource::on_parameter_event
(src) unreachable, as any event published to/parameter_events
must be of right name and type.Both issues lead to waste of cycles (first one by making unnecessary subscription and second one by doing redundant checks), and seem to need fixing. Could you share your thoughts on this?
Required Info: