Skip to content

Commit

Permalink
revert lock scope
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Sep 13, 2023
1 parent 54c2a77 commit b8ba42f
Showing 1 changed file with 15 additions and 18 deletions.
33 changes: 15 additions & 18 deletions src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -361,16 +361,13 @@ void SensorsPrivate::RunOnce()

// safety check to see if reset occurred while we're rendering
// avoid publishing outdated data if reset occurred
std::unique_lock<std::mutex> timeLock(this->renderMutex);
if (updateTimeApplied <= this->updateTime)
{
std::unique_lock<std::mutex> timeLock(this->renderMutex);
if (updateTimeApplied <= this->updateTime)
{
timeLock.unlock();
// publish data
GZ_PROFILE("RunOnce");
this->sensorManager.RunOnce(updateTimeApplied);
this->eventManager->Emit<events::Render>();
}
// publish data
GZ_PROFILE("RunOnce");
this->sensorManager.RunOnce(updateTimeApplied);
this->eventManager->Emit<events::Render>();
}

// re-enble sensors
Expand Down Expand Up @@ -742,17 +739,17 @@ void Sensors::PostUpdate(const UpdateInfo &_info,
std::unique_lock<std::mutex> lockSensors(this->dataPtr->sensorsMutex);
this->dataPtr->activeSensors =
std::move(this->dataPtr->sensorsToUpdate);
}

this->dataPtr->nextUpdateTime = this->dataPtr->NextUpdateTime(
this->dataPtr->sensorsToUpdate, _info.simTime);
this->dataPtr->nextUpdateTime = this->dataPtr->NextUpdateTime(
this->dataPtr->sensorsToUpdate, _info.simTime);

// Force scene tree update if there are sensors to be created or
// subscribes to the render events. This does not necessary force
// sensors to update. Only active sensors will be updated
this->dataPtr->forceUpdate =
(this->dataPtr->renderUtil.PendingSensors() > 0) ||
hasRenderConnections;
// Force scene tree update if there are sensors to be created or
// subscribes to the render events. This does not necessary force
// sensors to update. Only active sensors will be updated
this->dataPtr->forceUpdate =
(this->dataPtr->renderUtil.PendingSensors() > 0) ||
hasRenderConnections;
}
{
std::unique_lock<std::mutex> cvLock(this->dataPtr->renderMutex);
this->dataPtr->updateAvailable = true;
Expand Down

0 comments on commit b8ba42f

Please sign in to comment.