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 1 commit
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
30 changes: 4 additions & 26 deletions src/gui/GuiRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,9 @@ 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;

/////////////////////////////////////////////////
GuiRunner::GuiRunner(const std::string &_worldName)
{
Expand All @@ -63,29 +57,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
8 changes: 6 additions & 2 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,9 @@ namespace ignition::gazebo

/// \brief Transport node for making command requests
public: transport::Node node;

/// \brief Mutex to protect componentsModel
public: QMutex mutex;
};
}

Expand Down Expand Up @@ -337,6 +340,8 @@ void ComponentInspector::Update(const UpdateInfo &,
if (this->dataPtr->paused)
return;

QMutexLocker locker(&this->dataPtr->mutex);

auto componentTypes = _ecm.ComponentTypes(this->dataPtr->entity);

// List all components
Expand Down Expand Up @@ -431,10 +436,9 @@ void ComponentInspector::Update(const UpdateInfo &,
// Add component to list
else
{
// TODO(louise) Blocking here is not the best idea
QMetaObject::invokeMethod(&this->dataPtr->componentsModel,
Copy link
Contributor

Choose a reason for hiding this comment

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

If we the Update function is called from the Qt thread, I would think we shouldn't need to use invokeMethod

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 thought that as well but when I change this invokeMethod to be:

item = this->dataPtr->componentsModel.AddComponentType(typeId);

even after dfabb5c it seg faults here: https://github.com/ignitionrobotics/ign-gazebo/blob/95fad0d32e3c015bd377e76856fdd2c2129d033f/src/gui/plugins/component_inspector/ComponentInspector.cc#L648

Copy link
Contributor

Choose a reason for hiding this comment

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

I tried that, but it didn't crash for me for rolling_shapes.sdf. Which world did you try it on?

Copy link
Contributor

Choose a reason for hiding this comment

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

Changing QMetaObject::invokeMethod(&this->dataPtr->componentsModel, "RemoveComponentType",... to a regular functions seems to break functionality of the ComponentInspector even though it doesn't crash, so maybe it's better to leave it as is. It's using Qt::QueuedConnection, which I think means it's executed after the thread goes to sleep after calling all the UpdatePlugin functions. So the timing may be important to keep the functionality.

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 tried that, but it didn't crash for me for rolling_shapes.sdf. Which world did you try it on?

I tested shapes.sdf, the crash happens after you select one of the entities in the entity tree.

"AddComponentType",
Qt::BlockingQueuedConnection,
Qt::DirectConnection,
Q_RETURN_ARG(QStandardItem *, item),
Q_ARG(ignition::gazebo::ComponentTypeId, typeId));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ namespace ignition::gazebo::gui

/// \brief Whether the initial model set from XML has been setup.
public: bool xmlModelInitialized{false};

/// \brief Mutex to protect jointsModel
public: QMutex mutex;
};
}

Expand Down Expand Up @@ -178,6 +181,8 @@ void JointPositionController::Update(const UpdateInfo &,
{
IGN_PROFILE("JointPositionController::Update");

QMutexLocker locker(&this->dataPtr->mutex);

if (!this->dataPtr->xmlModelInitialized)
{
auto entity = _ecm.EntityByComponents(
Expand Down Expand Up @@ -241,10 +246,9 @@ 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,
Qt::DirectConnection,
Q_RETURN_ARG(QStandardItem *, item),
Q_ARG(Entity, jointEntity));
newItem = true;
Expand Down