Skip to content

Commit 6ab0bfe

Browse files
committed
Fix deadlock when publishing performance metrics
Currently the PublishPerformanceMetrics function is called within SensorManager.cc by each SensorContainer with protection by the mutex of each SensorContainer. This leads to a deadlock when a world has sensors in more than one container (i.e. more than one category of sensors) as described in gazebosim#2902. Since the PublishPerformanceMetrics function is not a member function of SensorContainer and uses only global variables, the function can be called by only the SensorManager thread instead of all the SensorContainer threads. It is also left unprotected by a mutex, as it may not be needed. Signed-off-by: Steve Peters <scpeters@openrobotics.org>
1 parent a9e1ee3 commit 6ab0bfe

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

gazebo/sensors/SensorManager.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -371,6 +371,8 @@ void SensorManager::Update(bool _force)
371371
// Only update if there are sensors
372372
if (this->sensorContainers[sensors::IMAGE]->sensors.size() > 0)
373373
this->sensorContainers[sensors::IMAGE]->Update(_force);
374+
375+
PublishPerformanceMetrics();
374376
}
375377

376378
//////////////////////////////////////////////////
@@ -853,8 +855,6 @@ void SensorManager::SensorContainer::Update(bool _force)
853855
{
854856
boost::recursive_mutex::scoped_lock lock(this->mutex);
855857

856-
PublishPerformanceMetrics();
857-
858858
if (this->sensors.empty())
859859
gzlog << "Updating a sensor container without any sensors.\n";
860860

0 commit comments

Comments
 (0)