Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Optimize sensor updates #1480

Merged
merged 6 commits into from
Jun 1, 2022
Merged
Show file tree
Hide file tree
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
18 changes: 18 additions & 0 deletions src/systems/air_pressure/AirPressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,24 @@ void AirPressure::PostUpdate(const UpdateInfo &_info,

if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the AirPressurePrivate::UpdatePressures function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->UpdateAirPressures(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
18 changes: 18 additions & 0 deletions src/systems/altimeter/Altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,24 @@ void Altimeter::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the AltimeterPrivate::UpdateAltimeters function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->UpdateAltimeters(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
18 changes: 18 additions & 0 deletions src/systems/force_torque/ForceTorque.cc
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,24 @@ void ForceTorque::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the ForceTorquePrivate::Update function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->Update(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
18 changes: 18 additions & 0 deletions src/systems/imu/Imu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,24 @@ void Imu::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the ImuPrivate::Update function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->Update(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
19 changes: 19 additions & 0 deletions src/systems/logical_camera/LogicalCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,25 @@ void LogicalCamera::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the LogicalCameraPrivate::UpdateLogicalCameras
// function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->UpdateLogicalCameras(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
18 changes: 18 additions & 0 deletions src/systems/magnetometer/Magnetometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,24 @@ void Magnetometer::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the MagnetometerPrivate::Update function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->Update(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
18 changes: 18 additions & 0 deletions src/systems/navsat/NavSat.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,24 @@ void NavSat::PostUpdate(const UpdateInfo &_info,
// Only update and publish if not paused.
if (!_info.paused)
{
// check to see if update is necessary
// we only update if there is at least one sensor that needs data
// and that sensor has subscribers.
// note: ign-sensors does its own throttling. Here the check is mainly
// to avoid doing work in the NavSat::Implementation::Update function
bool needsUpdate = false;
for (auto &it : this->dataPtr->entitySensorMap)
{
if (it.second->NextDataUpdateTime() <= _info.simTime &&
it.second->HasConnections())
{
needsUpdate = true;
break;
}
}
if (!needsUpdate)
return;

this->dataPtr->Update(_ecm);

for (auto &it : this->dataPtr->entitySensorMap)
Expand Down
66 changes: 66 additions & 0 deletions src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <map>
#include <set>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -186,6 +187,11 @@ class ignition::gazebo::systems::SensorsPrivate
/// \param[in] _ecm Entity component manager
public: void UpdateBatteryState(const EntityComponentManager &_ecm);

/// \brief Check if sensor has subscribers
/// \param[in] _sensor Sensor to check
/// \return True if the sensor has subscribers, false otherwise
public: bool HasConnections(sensors::RenderingSensor *_sensor) const;

/// \brief Use to optionally set the background color.
public: std::optional<math::Color> backgroundColor;

Expand Down Expand Up @@ -316,12 +322,34 @@ void SensorsPrivate::RunOnce()
this->scene->PreRender();
}

// disable sensors that have no subscribers to prevent doing unnecessary
// work
std::unordered_set<sensors::RenderingSensor *> tmpDisabledSensors;
this->sensorMaskMutex.lock();
for (auto id : this->sensorIds)
{
sensors::Sensor *s = this->sensorManager.Sensor(id);
auto rs = dynamic_cast<sensors::RenderingSensor *>(s);
if (rs->IsActive() && !this->HasConnections(rs))
{
rs->SetActive(false);
tmpDisabledSensors.insert(rs);
}
}
this->sensorMaskMutex.unlock();

{
// publish data
IGN_PROFILE("RunOnce");
this->sensorManager.RunOnce(this->updateTime);
}

// re-enble sensors
for (auto &rs : tmpDisabledSensors)
{
rs->SetActive(true);
}

{
IGN_PROFILE("PostRender");
// Update the scene graph manually to improve performance
Expand Down Expand Up @@ -805,6 +833,44 @@ std::string Sensors::CreateSensor(const Entity &_entity,
return sensor->Name();
}

//////////////////////////////////////////////////
bool SensorsPrivate::HasConnections(sensors::RenderingSensor *_sensor) const
{
if (!_sensor)
return true;

// \todo(iche033) Remove this function once a virtual
// sensors::RenderingSensor::HasConnections function is available
{
auto s = dynamic_cast<sensors::DepthCameraSensor *>(_sensor);
if (s)
return s->HasConnections();
}
{
auto s = dynamic_cast<sensors::GpuLidarSensor *>(_sensor);
if (s)
return s->HasConnections();
}
{
auto s = dynamic_cast<sensors::SegmentationCameraSensor *>(_sensor);
if (s)
return s->HasConnections();
}
{
auto s = dynamic_cast<sensors::ThermalCameraSensor *>(_sensor);
if (s)
return s->HasConnections();
}
{
auto s = dynamic_cast<sensors::CameraSensor *>(_sensor);
if (s)
return s->HasConnections();
}
ignwarn << "Unable to check connection count for sensor: " << _sensor->Name()
<< ". Unknown sensor type." << std::endl;
return true;
chapulina marked this conversation as resolved.
Show resolved Hide resolved
}

IGNITION_ADD_PLUGIN(Sensors, System,
Sensors::ISystemConfigure,
Sensors::ISystemUpdate,
Expand Down