ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ROS2 nodes don't "step" when Gazebo simulation is stepped forward

asked 2021-10-28 15:52:53 -0600

shonigmann gravatar image

updated 2021-11-02 11:54:40 -0600

We have a simulated robotic system running ROS2 Foxy, and we've noticed that the nodes relying on the Gazebo ROS interface remain frozen when we step the simulation forward by N iterations. Things work as expected when the simulation is unpaused, but when we pause the simulation and try to advance the simulation manually, we can see the Gazebo simulation time progresses but none of the ROS interfaces do anything.

For instance, we can look at the /clock topic, see that new timestamps are getting published while the simulation is unpaused, pause the simulation and no new messages are published, step the simulation in Gazebo forward by 10 seconds, and unpause the simulation and we see a sudden jump in the time being published to the new time.

We quickly tried this same experiment in ROS1 Melodic and did not have the same issue.

Has anyone encountered this issue before, or does anyone have any tips on getting ROS2 nodes to continue to function when a gazebo_ros simulation is stepped forward?

(Associated issue)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-11-02 12:00:10 -0600

shonigmann gravatar image

After a bit more digging, I think the issues we have been experiencing are due to the publisher "Throttler" checking the realTime clock instead of the simTime clock

void GazeboRosInitPrivate::PublishSimTime(const gazebo::common::UpdateInfo & _info)
{
  if (!throttler_.IsReady(_info.realTime)) {  // <-- HERE
    return;
  }

  rosgraph_msgs::msg::Clock clock;
  clock.clock = gazebo_ros::Convert<builtin_interfaces::msg::Time>(_info.simTime);
  clock_pub_->publish(clock);

For whatever reason, the realTime is not updated when stepping the simulation. As a result, the gazebo_ros interface never publishes clock updates when the simulation is paused and is being stepped. All other nodes relying on the /clock topic unsurprisingly stop working as expected.

In gazebo_ros_pkgs#1325, I suggest a simple 'fix' of simply changing:

if (!throttler_.IsReady(_info.realTime)) {

to:

if (!throttler_.IsReady(_info.simTime)) {

This does the trick for our purposes. However, it looks like it causes a few build tests to fail. I will try to investigate these to see if they are a concern, and will update this answer if anything comes up.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2021-10-28 15:52:53 -0600

Seen: 387 times

Last updated: Nov 02 '21