Skip to content

Commit

Permalink
Fix race condition when rendering the UI
Browse files Browse the repository at this point in the history
This fix depends on a fix in ign-rendering module, because it
depends on the new Camera::SwapFromThread function
Without it, compilation will fail

Affects gazebosim/gz-rendering#304

Signed-off-by: Matias N. Goldberg <dark_sylinc@yahoo.com.ar>
  • Loading branch information
darksylinc committed May 9, 2021
1 parent a9cfa0d commit 38e0a59
Show file tree
Hide file tree
Showing 2 changed files with 107 additions and 14 deletions.
62 changes: 55 additions & 7 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@
std::condition_variable g_renderCv;

Q_DECLARE_METATYPE(std::string)
Q_DECLARE_METATYPE(ignition::gazebo::RenderSync*)

namespace ignition
{
Expand Down Expand Up @@ -447,6 +448,45 @@ using namespace gazebo;

QList<QThread *> RenderWindowItemPrivate::threads;

/////////////////////////////////////////////////
void RenderSync::requestQtThreadToBlock(std::unique_lock<std::mutex> &lock)
{
this->renderStallState = RenderStallState::WorkerThreadRequested;
this->cv.wait(lock, [this]
{ return this->renderStallState == RenderStallState::QtThreadBlocked; });
}

/////////////////////////////////////////////////
void RenderSync::releaseQtThreadFromBlock(std::unique_lock<std::mutex> &lock)
{
this->renderStallState = RenderStallState::Unblocked;
lock.unlock();
this->cv.notify_one();
}

/////////////////////////////////////////////////
void RenderSync::waitForWorkerThread()
{
{
std::unique_lock<std::mutex> lock(this->mutex);
if(this->renderStallState == RenderStallState::WorkerThreadRequested)
{
// Worker thread asked us to wait!
this->renderStallState = RenderStallState::QtThreadBlocked;
lock.unlock();
// Wake up worker thread
this->cv.notify_one();
}
}

{
// Wait until we're clear to go
std::unique_lock<std::mutex> lock(this->mutex);
this->cv.wait(lock, [this]
{ return this->renderStallState == RenderStallState::Unblocked; });
}
}

/////////////////////////////////////////////////
IgnRenderer::IgnRenderer()
: dataPtr(new IgnRendererPrivate)
Expand All @@ -472,7 +512,7 @@ RenderUtil *IgnRenderer::RenderUtil() const
}

/////////////////////////////////////////////////
void IgnRenderer::Render()
void IgnRenderer::Render(RenderSync *renderSync)
{
rendering::ScenePtr scene = this->dataPtr->renderUtil.Scene();
if (!scene)
Expand All @@ -488,6 +528,8 @@ void IgnRenderer::Render()
IGN_PROFILE("IgnRenderer::Render");
if (this->textureDirty)
{
std::unique_lock<std::mutex> lock(renderSync->mutex);
renderSync->requestQtThreadToBlock(lock);
this->dataPtr->camera->SetImageWidth(this->textureSize.width());
this->dataPtr->camera->SetImageHeight(this->textureSize.height());
this->dataPtr->camera->SetAspectRatio(this->textureSize.width() /
Expand All @@ -498,6 +540,7 @@ void IgnRenderer::Render()
this->dataPtr->camera->PreRender();
}
this->textureDirty = false;
renderSync->releaseQtThreadFromBlock(lock);
}

// texture id could change so get the value in every render update
Expand Down Expand Up @@ -855,6 +898,8 @@ void IgnRenderer::Render()
// only has an effect in video recording lockstep mode
// this notifes ECM to continue updating the scene
g_renderCv.notify_one();

this->dataPtr->camera->SwapFromThread();
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -2168,10 +2213,11 @@ RenderThread::RenderThread()
{
RenderWindowItemPrivate::threads << this;
qRegisterMetaType<std::string>();
qRegisterMetaType<RenderSync*>("RenderSync*");
}

/////////////////////////////////////////////////
void RenderThread::RenderNext()
void RenderThread::RenderNext(RenderSync *renderSync)
{
this->context->makeCurrent(this->surface);

Expand All @@ -2188,7 +2234,7 @@ void RenderThread::RenderNext()
return;
}

this->ignRenderer.Render();
this->ignRenderer.Render(renderSync);

emit TextureReady(this->ignRenderer.textureId, this->ignRenderer.textureSize);
}
Expand Down Expand Up @@ -2251,7 +2297,7 @@ TextureNode::~TextureNode()
}

/////////////////////////////////////////////////
void TextureNode::NewTexture(int _id, const QSize &_size)
void TextureNode::NewTexture(uint _id, const QSize &_size)
{
this->mutex.lock();
this->id = _id;
Expand All @@ -2266,8 +2312,9 @@ void TextureNode::NewTexture(int _id, const QSize &_size)
/////////////////////////////////////////////////
void TextureNode::PrepareNode()
{
renderSync.waitForWorkerThread();
this->mutex.lock();
int newId = this->id;
uint newId = this->id;
QSize sz = this->size;
this->id = 0;
this->mutex.unlock();
Expand Down Expand Up @@ -2299,7 +2346,7 @@ void TextureNode::PrepareNode()

// This will notify the rendering thread that the texture is now being
// rendered and it can start rendering to the other one.
emit TextureInUse();
emit TextureInUse(&this->renderSync);
}
}

Expand Down Expand Up @@ -2442,7 +2489,8 @@ QSGNode *RenderWindowItem::updatePaintNode(QSGNode *_node,

// Get the production of FBO textures started..
QMetaObject::invokeMethod(this->dataPtr->renderThread, "RenderNext",
Qt::QueuedConnection);
Qt::QueuedConnection,
Q_ARG( RenderSync*, &node->renderSync ));
}

node->setRect(this->boundingRect());
Expand Down
59 changes: 52 additions & 7 deletions src/gui/plugins/scene3d/Scene3D.hh
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,45 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
private: std::unique_ptr<Scene3DPrivate> dataPtr;
};

class RenderSync
{
/// \brief Cond. variable to synchronize rendering on specific events
/// (e.g. texture resize) or for debugging (e.g. keep
/// all API calls sequential)
public: std::mutex mutex;

/// \brief Cond. variable to synchronize rendering on specific events
/// (e.g. texture resize) or for debugging (e.g. keep
/// all API calls sequential)
public: std::condition_variable cv;

public: enum class RenderStallState
{
/// All threads will continue as normal
Unblocked,
/// Worker thread requested Qt thread to be blocked; and is
/// waiting for Qt thread to see this
WorkerThreadRequested,
/// Qt thread saw WorkerThreadRequested, set the variable to
/// QtThreadBlocked; and is now waiting for worker thread to do
/// its thing and set it back to Unblocked so that Qt can resume
QtThreadBlocked
};

/// \brief See TextureNode::RenderSync::RenderStallState
public: RenderStallState renderStallState =
RenderStallState::Unblocked /*GUARDED_BY(sharedRenderMutex)*/;

/// \brief Must be called from worker thread when we want to block
/// \param[in] lock Acquired lock. Must be based on this->mutex
public: void requestQtThreadToBlock(std::unique_lock<std::mutex> &lock);
/// \brief Must be called from worker thread when we are done
/// \param[in] lock Acquired lock. Must be based on this->mutex
public: void releaseQtThreadFromBlock(std::unique_lock<std::mutex> &lock);
/// \brief Must be called from Qt thread periodically
public: void waitForWorkerThread();
};

/// \brief Ign-rendering renderer.
/// All ign-rendering calls should be performed inside this class as it makes
/// sure that opengl calls in the underlying render engine do not interfere
Expand All @@ -183,7 +222,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: ~IgnRenderer() override;

/// \brief Main render function
public: void Render();
public: void Render(RenderSync *renderSync);

/// \brief Initialize the render engine
public: void Initialize();
Expand Down Expand Up @@ -450,7 +489,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
bool _waitForTarget);

/// \brief Render texture id
public: GLuint textureId = 0u;
/// Values is constantly constantly cycled/swapped/changed
/// from a worker thread
/// Don't read this directly
public: GLuint textureId;

/// \brief Initial Camera pose
public: math::Pose3d cameraPose = math::Pose3d(0, 0, 2, 0, 0.4, 0);
Expand Down Expand Up @@ -484,7 +526,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: RenderThread();

/// \brief Render the next frame
public slots: void RenderNext();
public slots: void RenderNext(RenderSync *renderSync);

/// \brief Shutdown the thread and the render engine
public slots: void ShutDown();
Expand All @@ -496,7 +538,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// to be displayed
/// \param[in] _id GLuid of the opengl texture
/// \param[in] _size Size of the texture
signals: void TextureReady(int _id, const QSize &_size);
signals: void TextureReady(uint _id, const QSize &_size);

/// \brief Offscreen surface to render to
public: QOffscreenSurface *surface = nullptr;
Expand Down Expand Up @@ -730,29 +772,32 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// store the texture id and size and schedule an update on the window.
/// \param[in] _id OpenGL render texture Id
/// \param[in] _size Texture size
public slots: void NewTexture(int _id, const QSize &_size);
public slots: void NewTexture(uint _id, const QSize &_size);

/// \brief Before the scene graph starts to render, we update to the
/// pending texture
public slots: void PrepareNode();

/// \brief Signal emitted when the texture is being rendered and renderer
/// can start rendering next frame
signals: void TextureInUse();
signals: void TextureInUse(RenderSync *renderSync);

/// \brief Signal emitted when a new texture is ready to trigger window
/// update
signals: void PendingNewTexture();

/// \brief OpenGL texture id
public: int id = 0;
public: uint id = 0;

/// \brief Texture size
public: QSize size = QSize(0, 0);

/// \brief Mutex to protect the texture variables
public: QMutex mutex;

/// \brief See RenderSync
public: RenderSync renderSync;

/// \brief Qt's scene graph texture
public: QSGTexture *texture = nullptr;

Expand Down

0 comments on commit 38e0a59

Please sign in to comment.