-
Notifications
You must be signed in to change notification settings - Fork 481
Open
Labels
more-information-neededFurther information is requiredFurther information is requiredquestionFurther information is requestedFurther information is requested
Description
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::Nodeobject is created, a subscription is created, whilerclpy.Nodedoes not create one.
- In TimeSource::attachNode, a subscription to
/parameter_eventsis created viarclcpp::AsyncParametersClient::on_parameter_event, bindingTimeSource::on_parameter_eventcallback to the/parameter_eventstopic (src). - When
use_sim_timeparameter 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_eventcallback is invoked. - When invoked,
TimeSource::on_parameter_eventchecks 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. - The workflow above obviously works. However, I do not understand why
on_parameter_eventcannot 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? - In other words, can't the workflow of handling
set paramrequest be as simple as- (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_eventcallback invoked and en/disables ROS time ?
- (rcl & rmw) req handled -> param callback invoked, en/disables ROS time, and returns SetParametersResult
- Error checking code in
TimeSource::on_parameter_event()is not reachable.
- In the current workflow, parameters other than
use_sim_time, anduse_sim_timewith wrong types (i.e., other than bool) are rejected by the handler. - Obviously, nothing is published to
/parameter_eventsas param set is not successful, andTimeSource::on_parameter_eventcallback is not invoked. - This makes the filters and type checking routines of
TimeSource::on_parameter_event(src) unreachable, as any event published to/parameter_eventsmust 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:
- Operating System:
- Ubuntu 20.04
- Installation type:
- source installation
- Version or commit hash:
- branch foxy at 1fff1b7
- DDS implementation:
- Fast-RTPS (does not affect the issue)
- Client library (if applicable):
- rclcpp
Metadata
Metadata
Assignees
Labels
more-information-neededFurther information is requiredFurther information is requiredquestionFurther information is requestedFurther information is requested