ubi-agni / mujoco_ros_pkgs

Wrappers, tools and additional API's for using ROS with MuJoCo
68 stars 12 forks source link

Why reset() doesn't reset ROS time? #6

Closed rhaschke closed 1 year ago

rhaschke commented 1 year ago

Why do you remember last_time_ and start simulation with this time after reset() here: https://github.com/ubi-agni/mujoco_ros_pkgs/blob/e8baa92b317878501f4199e34bf6c7b7074639b1/mujoco_ros/src/mujoco_sim.cpp#L339-L340

Also, you use the ROS time for initialization: https://github.com/ubi-agni/mujoco_ros_pkgs/blob/e8baa92b317878501f4199e34bf6c7b7074639b1/mujoco_ros/src/mujoco_sim.cpp#L189-L193

and only later switch to sim time: https://github.com/ubi-agni/mujoco_ros_pkgs/blob/e8baa92b317878501f4199e34bf6c7b7074639b1/mujoco_ros/src/mujoco_sim.cpp#L258-L260

What's the reasoning behind this?

DavidPL1 commented 1 year ago

The reasoning behind keeping the ROS time is that other components operating in the same ROS environment depend on time-consistency. By resetting the time components may break. E.g. TF will detect a jump back in time, throw TF_OLD_DATA warnings and choose to ignore newly published TF data until last_time_ is reached. This behavior would break all components depending on TF.

DavidPL1 commented 1 year ago

After some research, I found that if, and only if, /use_sim_time is set in the launch file before starting any node, the TF buffer is cleared upon a jump back in time and the joint_state_publisher node re-publishes joint transforms. However, control still seems unable to handle this. I could not find the reason, but sometimes upon reset the robot stays in position, i.e. the controller sends a valid control signal, and sometimes the robot just drops to the floor without any signs of being actively controlled. Once the point in (ROS) time is reached, where the reset was previously issued, the robot starts being actuated again. Occasionally TF_OLD_DATA and TF_REPEATED_DATA warnings are still thrown. The behavior upon a time reset seems rather unstable.

To reproduce the issue checkout the fix_reset branch in this repo and start the following launch command and randomly reset the simulation form time to time: roslaunch franka_mujoco panda.launch controller:=effort_joint_trajectory_controller

rhaschke commented 1 year ago

I found that if, and only if, /use_sim_time is set in the launch file before starting any node, the TF buffer is cleared upon a jump back in time.

This matches to our source finding before. Only if /use_sim_time is set at node startup time, the node will use sim time! Changing this param later, doesn't have an effect, because the corresponding /clock subscriber is not created!

Thus, mujoco_ros (and also gazebo_ros) shouldn't not set /use_sim_time in hindsight, but bail out with a thick warning/error message indicating that /use_sim_time should be set in the launch file. The only exception might be the corresponding sim node being the one and only ROS node being active at that time...