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

use QTimer to update plugins #1095

Merged
merged 6 commits into from
Oct 15, 2021
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
9 changes: 7 additions & 2 deletions include/ignition/gazebo/gui/GuiRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,13 +60,18 @@ class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject
/// \param[in] _res Response containing new state.
private: void OnStateAsyncService(const msgs::SerializedStepMap &_res);

/// \brief Callback when a new state is received from the server.
/// \brief Callback when a new state is received from the server. Actual
/// updating of the ECM is delegated to OnStateQt
/// \param[in] _msg New state message.
private: void OnState(const msgs::SerializedStepMap &_msg);

/// \brief Called by the Qt thread to update the ECM with new state
/// \param[in] _msg New state message.
private: Q_INVOKABLE void OnStateQt(const msgs::SerializedStepMap &_msg);

/// \brief Update the plugins.
/// \todo(anyone) Move to GuiRunner::Implementation when porting to v5
private: void UpdatePlugins();
private: Q_INVOKABLE void UpdatePlugins();

/// \brief Entity-component manager.
private: gazebo::EntityComponentManager ecm;
Expand Down
51 changes: 21 additions & 30 deletions src/gui/GuiRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,19 +30,15 @@
using namespace ignition;
using namespace gazebo;

/// \todo(anyone) Move to GuiRunner::Implementation when porting to v5
/// \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;
// Register SerializedStepMap to the Qt meta type system so we can pass objects
// of this type in QMetaObject::invokeMethod
Q_DECLARE_METATYPE(msgs::SerializedStepMap)

/////////////////////////////////////////////////
GuiRunner::GuiRunner(const std::string &_worldName)
{
qRegisterMetaType<msgs::SerializedStepMap>();

this->setProperty("worldName", QString::fromStdString(_worldName));

auto win = gui::App()->findChild<ignition::gui::MainWindow *>();
Expand All @@ -63,29 +59,13 @@ GuiRunner::GuiRunner(const std::string &_worldName)
this->RequestState();

// Periodically update the plugins
// \todo(anyone) Move the global variables to GuiRunner::Implementation on v5
gRunning = true;
gUpdateThread = std::thread([&]()
{
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));
}
});
QPointer<QTimer> timer = new QTimer(this);
connect(timer, &QTimer::timeout, this, &GuiRunner::UpdatePlugins);
azeey marked this conversation as resolved.
Show resolved Hide resolved
timer->start(33);
}

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

/////////////////////////////////////////////////
void GuiRunner::RequestState()
Expand Down Expand Up @@ -131,8 +111,19 @@ void GuiRunner::OnState(const msgs::SerializedStepMap &_msg)
{
IGN_PROFILE_THREAD_NAME("GuiRunner::OnState");
IGN_PROFILE("GuiRunner::Update");
// Since this function may be called from a transport thread, we push the
// OnStateQt function to the queue so that its called from the Qt thread. This
// ensures that only one thread has access to the ecm and updateInfo
// variables.
QMetaObject::invokeMethod(this, "OnStateQt", Qt::QueuedConnection,
Q_ARG(msgs::SerializedStepMap, _msg));
}

std::lock_guard<std::mutex> lock(gUpdateMutex);
/////////////////////////////////////////////////
void GuiRunner::OnStateQt(const msgs::SerializedStepMap &_msg)
{
IGN_PROFILE_THREAD_NAME("Qt thread");
IGN_PROFILE("GuiRunner::Update");
this->ecm.SetState(_msg.state());

// Update all plugins
Expand Down
7 changes: 1 addition & 6 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -431,12 +431,7 @@ void ComponentInspector::Update(const UpdateInfo &,
// Add component to list
else
{
// TODO(louise) Blocking here is not the best idea
QMetaObject::invokeMethod(&this->dataPtr->componentsModel,
"AddComponentType",
Qt::BlockingQueuedConnection,
Q_RETURN_ARG(QStandardItem *, item),
Q_ARG(ignition::gazebo::ComponentTypeId, typeId));
item = this->dataPtr->componentsModel.AddComponentType(typeId);
}

if (nullptr == item)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -241,12 +241,7 @@ void JointPositionController::Update(const UpdateInfo &,
// Add joint to list
else
{
// TODO(louise) Blocking here is not the best idea
QMetaObject::invokeMethod(&this->dataPtr->jointsModel,
"AddJoint",
Qt::BlockingQueuedConnection,
Q_RETURN_ARG(QStandardItem *, item),
Q_ARG(Entity, jointEntity));
item = this->dataPtr->jointsModel.AddJoint(jointEntity);
newItem = true;
}

Expand Down