ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
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.