From 591f88c462048b0c2f168a28284c68e331093dd7 Mon Sep 17 00:00:00 2001 From: kennysharma Date: Mon, 6 Feb 2017 17:13:39 +0100 Subject: [PATCH] Ensure gazebo_ros_camera Publishes After Reset After a simulation reset, gazebo_ros_camera does not publish images because it is using its internal (and not reset by the world event) last_update_time_ rather than it's parent sensor's update time. I think all of these issues were fixed in the main gazebo repo in the last major release or two, but it looks like the plugins were not fully updated. There are likely similar issues in the other plugins that should be looked into (by someone who is more familiar with them). --- gazebo_plugins/src/gazebo_ros_camera.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_plugins/src/gazebo_ros_camera.cpp b/gazebo_plugins/src/gazebo_ros_camera.cpp index 8367b7faa..4d36e4937 100644 --- a/gazebo_plugins/src/gazebo_ros_camera.cpp +++ b/gazebo_plugins/src/gazebo_ros_camera.cpp @@ -89,7 +89,7 @@ void GazeboRosCamera::OnNewFrame(const unsigned char *_image, if ((*this->image_connect_count_) > 0) { common::Time cur_time = this->world_->GetSimTime(); - if (cur_time - this->last_update_time_ >= this->update_period_) + if (cur_time - this->sensor_update_time_ >= this->update_period_) { this->PutCameraData(_image); this->PublishCameraInfo();