ros2_controllers icon indicating copy to clipboard operation
ros2_controllers copied to clipboard

joint_state_broadcaster always using sim time

Open ghost opened this issue 3 years ago • 10 comments
trafficstars

Describe the bug Although the use_sim_time param of my joint_state_broadcaster node is False, the joint_state messages use the sim time

root@logi-XMG-CORE-REN-M20:/data/workspace# ros2 param get /agv2/joint_state_broadcaster use_sim_time
Boolean value is: False
root@logi-XMG-CORE-REN-M20:/data/workspace# ros2 topic echo /agv2/joint_states 
header:
  stamp:
    sec: 382
    nanosec: 750000000
  frame_id: ''
name: [left_wheel_joint, right_wheel_joint, forks_lift_joint, steering_joint, wheel_front_joint]
position: [-0.04167691639912441, 0.06193700121401591, 0.0007567684930120034, 0.00028650526121598574, 0.0035649638805272943]
velocity: [.nan, .nan, .nan, .nan, 0.0021658606914621084]
effort: [.nan, .nan, .nan, .nan, .nan]
---
header:
  stamp:
    sec: 382
    nanosec: 770000000
  frame_id: ''
name: [left_wheel_joint, right_wheel_joint, forks_lift_joint, steering_joint, wheel_front_joint]
position: [-0.04145976361109849, 0.06187559532052589, 0.0007608556058199859, 0.00044230279667445416, 0.0037088602539263604]
velocity: [.nan, .nan, .nan, .nan, 0.0001895595352630266]
effort: [.nan, .nan, .nan, .nan, .nan]
---
root@logi-XMG-CORE-REN-M20:/data/workspace# ros2 topic info -v /agv2/joint_states 
Type: sensor_msgs/msg/JointState

Publisher count: 1

Node name: joint_state_broadcaster
Node namespace: /agv2
Topic type: sensor_msgs/msg/JointState
Endpoint type: PUBLISHER
GID: b1.51.10.01.38.16.eb.32.c4.9e.10.ba.00.01.67.03.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  Durability: VOLATILE
  Lifespan: 9223372036854775807 nanoseconds
  Deadline: 9223372036854775807 nanoseconds
  Liveliness: AUTOMATIC
  Liveliness lease duration: 9223372036854775807 nanoseconds

Subscription count: 1

Node name: robot_state_publisher
Node namespace: /agv2
Topic type: sensor_msgs/msg/JointState
Endpoint type: SUBSCRIPTION
GID: 09.79.10.01.db.7b.c9.ee.d1.9a.f8.fb.00.00.18.04.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  Durability: VOLATILE
  Lifespan: 9223372036854775807 nanoseconds
  Deadline: 9223372036854775807 nanoseconds
  Liveliness: AUTOMATIC
  Liveliness lease duration: 9223372036854775807 nanoseconds

agv2:
  controller_manager:
    ros__parameters:
      update_rate: 50 # Hz
      use_sim_time: False

      fork_controller:
        type: joint_trajectory_controller/JointTrajectoryController # velocity_controllers/JointPositionController should be enough but not ported to ROS2 yet https://github.com/ros-controls/ros2_controllers/tree/foxy/velocity_controllers/src

      steering_controller:
        type: position_controllers/JointGroupPositionController # position_controllers/JointPositionController should be enough but not ported to ROS2 yet https://github.com/ros-controls/ros2_controllers/tree/master/position_controllers/src

      wheel_speed_controller:
        type: velocity_controllers/JointGroupVelocityController

      joint_state_broadcaster:
        type: joint_state_broadcaster/JointStateBroadcaster

  fork_controller:
    ros__parameters:
      joints:
        - forks_lift_joint
      command_interfaces:
        - position
      state_interfaces:
        - position

  steering_controller:
    ros__parameters:
      joints:
        - steering_joint
      interface_name: position
      command_interfaces:
        - position
      state_interfaces:
        - position

  wheel_speed_controller:
    ros__parameters:
      joints:
        - wheel_front_joint
      command_interfaces:
        - velocity
      state_interfaces:
        - velocity
        - position

Expected behavior Supposed to use system time like for other controllers, e.g:

root@logi-XMG-CORE-REN-M20:/data/workspace# ros2 param get /agv2/fork_controller use_sim_time  
Boolean value is: False
root@logi-XMG-CORE-REN-M20:/data/workspace# ros2 topic echo /agv2/fork_controller/state
header:
  stamp:
    sec: 1643194090
    nanosec: 195141890
  frame_id: ''
joint_names: [forks_lift_joint]
desired:
  positions: []
  velocities: []
  accelerations: []
  effort: []
  time_from_start:
    sec: 0
    nanosec: 0
actual:

Environment

  • OS: Ubuntu 20
  • Version: Galactic
  • Using gazebo_ros2_control
  • Does namespacing count as something unusual?

Additional context Add any other context about the problem here, especially include any modifications to any ros2_controllers that relate to this issue.

ghost avatar Jan 26 '22 10:01 ghost

P.S: I'm ghost, deleted the other account

tonynajjar avatar Jan 26 '22 13:01 tonynajjar

Hey @tonynajjar ,

ros2_control uses the same time source throughout the framework, ROS time. If you are running Gazebo, this will be sim time.

Each controller/broadcaster is passed time through the update() function which we favour over node->now() as that could introduce inconsistencies. Unfortunately, the joint_trajectory_controller did not get fully refactored yet, I'll open an issue for this.

So I'd say this is not a bug but very much intended from our end. What is your purpose of trying to mix different time sources?

bmagyar avatar Jan 29 '22 08:01 bmagyar

https://github.com/ros-controls/ros2_controllers/issues/290

bmagyar avatar Jan 29 '22 08:01 bmagyar

Thank you for your answer @bmagyar. So the bug is actually in joint_trajectory_controller for using system time

I'm not trying to mix up time sources, I'm trying to use system time everywhere, which works for all my nodes except joint_state_broadcaster. Is it unusual to use system time when running gazebo simulation? Any harm in that if all nodes are consistent and use system time?

Besides what is the point of the use_sim_time parameter if the time source is predetermined no matter the parameter.

Thanks!

tonynajjar avatar Jan 29 '22 08:01 tonynajjar

So the bug is actually in joint_trajectory_controller for using system time

Yes this is correct. Actually the error is using node->now(). That is the reason why you can set it using use_sim_time parameter.

I'm not trying to mix up time sources, I'm trying to use system time everywhere, which works for all my nodes except joint_state_broadcaster. Is it unusual to use system time when running gazebo simulation?

IMO, yes, if you are using a fully simulated environment, then you want to use simulation time. Otherwise, you can get problems with synchronization. For example: if you are integrating positions from velocities in two nodes with different time sources: delta T will be different. The source of this is that simulation, if complex, not always runs in the real time (system time), but slower.

Any harm in that if all nodes are consistent and use system time?

There is no harm in it, but you have to somehow convince Gazebo to use system time too. Although in this case, the simulation can become unstable is Gazebo does not manage to calculate all the physics in real-time. Depending on the concrete scenario, those effects could have different magnitudes.

Besides what is the point of the use_sim_time parameter if the time source is predetermined no matter the parameter.

I am guessing is to tell “external” nodes that are not connected directly with the simulator as ros2_control is, e.g., MoveIt nodes, to not use system, but simulated time. In ros2_control context this does not make sense, but we are inheriting node classes in our controller, so the parameter will be there available.

@bmagyar should we add warning in ControllerInterface if this parameter is defined that there is no influence on ros2_control controllers?

destogl avatar Jan 29 '22 10:01 destogl

Alright thank you for the explanations, makes sense. Feel free to close this issue

tonynajjar avatar Jan 29 '22 16:01 tonynajjar

Well.. gazebo can only pretend to use system time as it scales time dynamically based on computational load... So sometimes time may be faster or slower, hence why in simulation cases we always want to let the simulator tell is what time it is.

On Sat, 29 Jan 2022, 16:03 Tony Najjar, @.***> wrote:

Alright thank you for the explanations, makes sense. Feel free to close this issue

— Reply to this email directly, view it on GitHub https://github.com/ros-controls/ros2_controllers/issues/289#issuecomment-1024937981, or unsubscribe https://github.com/notifications/unsubscribe-auth/AA24PYOANXPDPPVSIVRRDCLUYQFUZANCNFSM5M2WL6UA . Triage notifications on the go with GitHub Mobile for iOS https://apps.apple.com/app/apple-store/id1477376905?ct=notification-email&mt=8&pt=524675 or Android https://play.google.com/store/apps/details?id=com.github.android&referrer=utm_campaign%3Dnotification-email%26utm_medium%3Demail%26utm_source%3Dgithub.

You are receiving this because you were mentioned.Message ID: @.***>

bmagyar avatar Jan 29 '22 16:01 bmagyar

hence why in simulation cases we always want to let the simulator tell is what time it is.

This is optional for a reason. Folks could be doing gazebo and hardware-in-the-loop at the same time.

Timple avatar Jan 29 '22 16:01 Timple

ros2_control will use the one and only ROS time passed to it by whoever manages the controller_manager update loop: gazebo or ros2_control_node or others.

Mixing time is not healthy but if you still want it, do the legwork.

On Sat, 29 Jan 2022, 16:19 Tim Clephas, @.***> wrote:

hence why in simulation cases we always want to let the simulator tell is what time it is.

This is optional for a reason. Folks could be doing gazebo and hardware-in-the-loop at the same time.

— Reply to this email directly, view it on GitHub https://github.com/ros-controls/ros2_controllers/issues/289#issuecomment-1024940891, or unsubscribe https://github.com/notifications/unsubscribe-auth/AA24PYO5W4AY2MZGR5MHGNLUYQHSRANCNFSM5M2WL6UA . Triage notifications on the go with GitHub Mobile for iOS https://apps.apple.com/app/apple-store/id1477376905?ct=notification-email&mt=8&pt=524675 or Android https://play.google.com/store/apps/details?id=com.github.android&referrer=utm_campaign%3Dnotification-email%26utm_medium%3Demail%26utm_source%3Dgithub.

You are receiving this because you were mentioned.Message ID: @.***>

bmagyar avatar Jan 29 '22 17:01 bmagyar

ros2_control will use the one and only ROS time

👍 That is all that should be 🙂

Timple avatar Jan 29 '22 17:01 Timple