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();