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

Limit scene broadcast publications when paused #497

Merged
merged 12 commits into from
Feb 26, 2021
4 changes: 4 additions & 0 deletions include/ignition/gazebo/gui/GuiRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@ class IGNITION_GAZEBO_VISIBLE GuiRunner : public QObject

/// \brief Latest update info
private: UpdateInfo updateInfo;

/// \brief Update the plugins.
/// \todo(anyone) Move to a private data class.
private: void UpdatePlugins();
};
}
}
Expand Down
45 changes: 41 additions & 4 deletions src/gui/GuiRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,15 @@
using namespace ignition;
using namespace gazebo;

/// \brief Flag used to end the gUpdateThread.
static bool gRunning = false;

/// \brief Mutex to protect the plugin update.
static std::mutex gUpdateMutex;

/// \brief The plugin update thread..
static std::thread gUpdateThread;
chapulina marked this conversation as resolved.
Show resolved Hide resolved

/////////////////////////////////////////////////
GuiRunner::GuiRunner(const std::string &_worldName)
{
Expand All @@ -51,10 +60,32 @@ GuiRunner::GuiRunner(const std::string &_worldName)
<< std::endl;

this->RequestState();

// Periodically update the plugins
// \todo(anyone) Pimplize GuiRunner and move these global variables to the
// private class.
gRunning = true;
gUpdateThread = std::thread([&]()
Copy link
Contributor

Choose a reason for hiding this comment

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

This will increase the number of updates while unpaused. I don't think it may cause immediate issues though, just something to keep an eye on.

{
while (gRunning)
{
{
std::lock_guard<std::mutex> lock(gUpdateMutex);
this->UpdatePlugins();
}
// This is roughly a 30Hz update rate.
std::this_thread::sleep_for(std::chrono::milliseconds(33));
}
});
}

/////////////////////////////////////////////////
GuiRunner::~GuiRunner() = default;
GuiRunner::~GuiRunner()
{
gRunning = false;
if (gUpdateThread.joinable())
gUpdateThread.join();
}

/////////////////////////////////////////////////
void GuiRunner::RequestState()
Expand Down Expand Up @@ -108,16 +139,22 @@ void GuiRunner::OnState(const msgs::SerializedStepMap &_msg)
IGN_PROFILE_THREAD_NAME("GuiRunner::OnState");
IGN_PROFILE("GuiRunner::Update");

std::lock_guard<std::mutex> lock(gUpdateMutex);
this->ecm.SetState(_msg.state());

// Update all plugins
this->updateInfo = convert<UpdateInfo>(_msg.stats());
this->UpdatePlugins();
this->ecm.ClearNewlyCreatedEntities();
this->ecm.ProcessRemoveEntityRequests();
}

/////////////////////////////////////////////////
void GuiRunner::UpdatePlugins()
{
auto plugins = gui::App()->findChildren<GuiSystem *>();
for (auto plugin : plugins)
{
plugin->Update(this->updateInfo, this->ecm);
}
this->ecm.ClearNewlyCreatedEntities();
this->ecm.ProcessRemoveEntityRequests();
}

29 changes: 22 additions & 7 deletions src/systems/scene_broadcaster/SceneBroadcaster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,9 @@ class ignition::gazebo::systems::SceneBroadcasterPrivate

/// \brief A list of async state requests
public: std::unordered_set<std::string> stateRequests;

/// \brief Stores change event information during PreUpdate.
public: bool changeEvent{false};
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -239,6 +242,16 @@ void SceneBroadcaster::Configure(
}
}

//////////////////////////////////////////////////
void SceneBroadcaster::PreUpdate(const UpdateInfo &_info,
EntityComponentManager &_ecm)
{
bool jumpBackInTime = _info.dt < std::chrono::steady_clock::duration::zero();
this->dataPtr->changeEvent = _ecm.HasEntitiesMarkedForRemoval() ||
_ecm.HasNewEntities() || _ecm.HasOneTimeComponentChanges() ||
jumpBackInTime;
chapulina marked this conversation as resolved.
Show resolved Hide resolved
}

//////////////////////////////////////////////////
void SceneBroadcaster::PostUpdate(const UpdateInfo &_info,
const EntityComponentManager &_manager)
Expand Down Expand Up @@ -272,14 +285,15 @@ void SceneBroadcaster::PostUpdate(const UpdateInfo &_info,
// Throttle here instead of using transport::AdvertiseMessageOptions so that
// we can skip the ECM serialization
bool jumpBackInTime = _info.dt < std::chrono::steady_clock::duration::zero();
this->dataPtr->changeEvent = this->dataPtr->changeEvent ||
_manager.HasEntitiesMarkedForRemoval() ||
_manager.HasNewEntities() || _manager.HasOneTimeComponentChanges() ||
jumpBackInTime;
auto now = std::chrono::system_clock::now();
bool changeEvent = _manager.HasEntitiesMarkedForRemoval() ||
_manager.HasNewEntities() || _manager.HasOneTimeComponentChanges() ||
jumpBackInTime;
bool itsPubTime = now - this->dataPtr->lastStatePubTime >
this->dataPtr->statePublishPeriod;
bool itsPubTime = !_info.paused && (now - this->dataPtr->lastStatePubTime >
this->dataPtr->statePublishPeriod);
auto shouldPublish = this->dataPtr->statePub.HasConnections() &&
(changeEvent || itsPubTime);
(this->dataPtr->changeEvent || itsPubTime);

if (this->dataPtr->stateServiceRequest || shouldPublish)
{
Expand All @@ -289,7 +303,7 @@ void SceneBroadcaster::PostUpdate(const UpdateInfo &_info,
set(this->dataPtr->stepMsg.mutable_stats(), _info);

// Publish full state if there are change events
if (changeEvent || this->dataPtr->stateServiceRequest)
if (this->dataPtr->changeEvent || this->dataPtr->stateServiceRequest)
{
_manager.State(*this->dataPtr->stepMsg.mutable_state(), {}, {}, true);
}
Expand Down Expand Up @@ -917,6 +931,7 @@ void SceneBroadcasterPrivate::RemoveFromGraph(const Entity _entity,
IGNITION_ADD_PLUGIN(SceneBroadcaster,
ignition::gazebo::System,
SceneBroadcaster::ISystemConfigure,
SceneBroadcaster::ISystemPreUpdate,
SceneBroadcaster::ISystemPostUpdate)

// Add plugin alias so that we can refer to the plugin without the version
Expand Down
7 changes: 7 additions & 0 deletions src/systems/scene_broadcaster/SceneBroadcaster.hh
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ namespace systems
class IGNITION_GAZEBO_VISIBLE SceneBroadcaster:
public System,
public ISystemConfigure,
public ISystemPreUpdate,
public ISystemPostUpdate
{
/// \brief Constructor
Expand All @@ -55,6 +56,12 @@ namespace systems
EntityComponentManager &_ecm,
EventManager &_eventMgr) final;

// Documentation inherited
public: void PreUpdate(
const ignition::gazebo::UpdateInfo &_info,
ignition::gazebo::EntityComponentManager &_ecm) override;

// Documentation inherited
public: void PostUpdate(const UpdateInfo &_info,
const EntityComponentManager &_ecm) final;

Expand Down