Skip to content
Draft
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 25 additions & 1 deletion src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <atomic>
#include <chrono>
#include <mutex>
#include <set>
#include <unordered_map>
#include <unordered_set>
Expand Down Expand Up @@ -867,7 +868,7 @@ void Sensors::Configure(const Entity &/*_id*/,
}

//////////////////////////////////////////////////
void Sensors::Reset(const UpdateInfo &_info, EntityComponentManager &)
void Sensors::Reset(const UpdateInfo &_info, EntityComponentManager &_ecm)
{
GZ_PROFILE("Sensors::Reset");

Expand Down Expand Up @@ -899,6 +900,17 @@ void Sensors::Reset(const UpdateInfo &_info, EntityComponentManager &)
this->dataPtr->updateTimeToApply = _info.simTime;
this->dataPtr->updateTimeApplied = _info.simTime;
}

{
std::unique_lock<std::mutex> lock(this->dataPtr->renderUtilMutex);
this->dataPtr->updateTimeCv.wait(lock, [this]()
{
return !this->dataPtr->updateAvailable ||
(this->dataPtr->updateTimeToApply ==
this->dataPtr->updateTimeApplied);
});
this->dataPtr->renderUtil.UpdateFromECM(_info, _ecm);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I arrived at a very similar fix. I had this call inside the mutex lock block a few lines above, i.e.

    std::unique_lock<std::mutex> lock2(this->dataPtr->renderUtilMutex);
    this->dataPtr->updateTime =  _info.simTime;
    this->dataPtr->updateTimeToApply =  _info.simTime;
    this->dataPtr->updateTimeApplied =  _info.simTime;
    this->dataPtr->renderUtil.UpdateFromECM(_info, _ecm);

but want to check, does this need to be in a separate block with the wait condition?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not 100% sure. Did it work for you? I saw the comment

GZ_PROFILE("UpdateFromECM");
// Make sure we do not override the state in renderUtil if there are
// still ECM changes that still need to be propagated to the scene,
// i.e. wait until renderUtil.Update(), has taken place in the
// rendering thread
std::unique_lock<std::mutex> lock(this->dataPtr->renderUtilMutex);
this->dataPtr->updateTimeCv.wait(lock, [this]()

which made me think it was necessary.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yeah it worked for me.

My thinking is that we could just override the state in renderUtil without waiting for any pending updates (updates from before the reset) to be applied because it's going to be reset to the initial state anyway.

}
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -1125,6 +1137,18 @@ std::string Sensors::CreateSensor(const Entity &_entity,
return std::string();
}

// Bail if we already have the sensor
auto entityIt = this->dataPtr->entityToIdMap.find(_entity);
if (entityIt != this->dataPtr->entityToIdMap.end())
{
sensors::Sensor *s = this->dataPtr->sensorManager.Sensor(entityIt->second);
// TODO(azeey): Don't warn if there has been a Reset.
if (s) {
gzwarn << "Sensor already exists: " << _entity << "\n";
return s->Name();
}
}

// Create within gz-sensors
sensors::Sensor *sensor{nullptr};
if (_sdf.Type() == sdf::SensorType::CAMERA)
Expand Down
Loading