Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Simulation time in replay mode #317

Open
JulioPlaced opened this issue Mar 27, 2024 · 3 comments
Open

Simulation time in replay mode #317

JulioPlaced opened this issue Mar 27, 2024 · 3 comments
Assignees
Labels
bug Something isn't working question Further information is requested

Comments

@JulioPlaced
Copy link

When replaying a recorded bag (using replay.launch.xml), the deserialized packets will be assigned the current ROS time instead of the simulated time (available in /clock topic). This causes the deserialized points/IMU to be desynchronized from other topics in the bag.

As far as we understand, even with use_sim_time=true, the call to rclcpp::Clock(RCL_ROS_TIME).now() (used here) is not able to subscribe to /clock itself; therefore it always returns the current ROS time. In ROS2 the simulation time (from /clock) is only accessible from a node, e.g. using node->now().

Screenshots
Desynchronization example between GPS (with recorded time), clock (simulated time) and deserialized ouster points (using current ROS time)
time_diff

We've coded a workaround that passes the node from os_cloud_node.cpp to the LidarPacketHandler and ImuPacketHandler classes, but we're wondering if this issue has been identified or addressed before. Otherwise we're happy to share it.

Platform:

  • Ouster Sensor: OS-1
  • ROS version/distro: Humble
  • Operating System: Linux
  • Machine Architecture: x64
@JulioPlaced JulioPlaced added the question Further information is requested label Mar 27, 2024
@Samahu
Copy link
Contributor

Samahu commented Apr 16, 2024

Hi @JulioPlaced, Although I have previously thought about this issue I have never looked in depth into replaying bag files storing raw sensor packets. Your question definitely sheds light on the issue. This is probably why I kept the timestamp_mode parameter available to users even within replay. Have you actually tried to replay the bag file with timestamp_mode set to TIME_FROM_ROS_TIME?

@Samahu Samahu self-assigned this Apr 16, 2024
@JulioPlaced
Copy link
Author

Hello @Samahu. Yes, timestamp_mode is set to TIME_FROM_ROS_TIME, and it is in fact retrieving ROS time (using rclcpp::Clock(RCL_ROS_TIME).now()). The problem with this time is that it is the current ROS time, not the ROS time at the time of recording.
As far as I understand, the only way to access the simulation time in ROS2 is from within a node, since you have to subscribe to /clock.
Therefore, instead of using rclcpp::Clock(RCL_ROS_TIME).now() here and here, we'd need to call node->now(). The first retrieves current ROS time whereas the second one subscribes to /clock and gets sim time.
Let me know if that makes sense.

@Samahu
Copy link
Contributor

Samahu commented Apr 17, 2024

Hello @Samahu. Yes, timestamp_mode is set to TIME_FROM_ROS_TIME, and it is in fact retrieving ROS time (using rclcpp::Clock(RCL_ROS_TIME).now()). The problem with this time is that it is the current ROS time, not the ROS time at the time of recording. As far as I understand, the only way to access the simulation time in ROS2 is from within a node, since you have to subscribe to /clock. Therefore, instead of using rclcpp::Clock(RCL_ROS_TIME).now() here and here, we'd need to call node->now(). The first retrieves current ROS time whereas the second one subscribes to /clock and gets sim time. Let me know if that makes sense.

Yeah that makes sense

@Samahu Samahu added the bug Something isn't working label Apr 17, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants