Skip to content

Issues around use_sim_time parameter callback handling in TimeSource #1758

@squizz617

Description

@squizz617

Hi.
I was cross-checking ros2 client libraries for API consistency, and came across these issues that needs fixing in my opinion.

  1. When an rclcpp::Node object is created, a subscription is created, while rclpy.Node does not create one.
  • In TimeSource::attachNode, a subscription to /parameter_events is created via rclcpp::AsyncParametersClient::on_parameter_event, binding TimeSource::on_parameter_event callback to the /parameter_events topic (src).
  • When use_sim_time parameter is set, e.g., through ros2 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.
  • When invoked, TimeSource::on_parameter_event checks if the event belongs to the node and is use_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_event cannot just be a part of the inline function that's registered as a parameter callback here. Doesn't sim_time_cb_handler_ exist specifically for this purpose?
  • In other words, can't the workflow of handling set param request 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_event callback invoked and en/disables ROS time ?
  1. Error checking code in TimeSource::on_parameter_event() is not reachable.
  • In the current workflow, parameters other than use_sim_time, and use_sim_time with wrong types (i.e., other than bool) are rejected by the handler.
  • Obviously, nothing is published to /parameter_events as param set is not successful, and TimeSource::on_parameter_event callback is not invoked.
  • This makes the filters and type checking routines of 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:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • source installation
  • Version or commit hash:
  • DDS implementation:
    • Fast-RTPS (does not affect the issue)
  • Client library (if applicable):
    • rclcpp

Metadata

Metadata

Assignees

No one assigned

    Labels

    more-information-neededFurther information is requiredquestionFurther information is requested

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions