From 38e0a5966efdb79e2e2dea02f01f2d4c53c2550a Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 18 Apr 2021 20:03:33 -0300 Subject: [PATCH 1/9] Fix race condition when rendering the UI 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 ignitionrobotics/ign-rendering#304 Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 62 ++++++++++++++++++++++++++---- src/gui/plugins/scene3d/Scene3D.hh | 59 ++++++++++++++++++++++++---- 2 files changed, 107 insertions(+), 14 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 3068321270..32515a8280 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -76,6 +76,7 @@ std::condition_variable g_renderCv; Q_DECLARE_METATYPE(std::string) +Q_DECLARE_METATYPE(ignition::gazebo::RenderSync*) namespace ignition { @@ -447,6 +448,45 @@ using namespace gazebo; QList RenderWindowItemPrivate::threads; +///////////////////////////////////////////////// +void RenderSync::requestQtThreadToBlock(std::unique_lock &lock) +{ + this->renderStallState = RenderStallState::WorkerThreadRequested; + this->cv.wait(lock, [this] + { return this->renderStallState == RenderStallState::QtThreadBlocked; }); +} + +///////////////////////////////////////////////// +void RenderSync::releaseQtThreadFromBlock(std::unique_lock &lock) +{ + this->renderStallState = RenderStallState::Unblocked; + lock.unlock(); + this->cv.notify_one(); +} + +///////////////////////////////////////////////// +void RenderSync::waitForWorkerThread() +{ + { + std::unique_lock 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 lock(this->mutex); + this->cv.wait(lock, [this] + { return this->renderStallState == RenderStallState::Unblocked; }); + } +} + ///////////////////////////////////////////////// IgnRenderer::IgnRenderer() : dataPtr(new IgnRendererPrivate) @@ -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) @@ -488,6 +528,8 @@ void IgnRenderer::Render() IGN_PROFILE("IgnRenderer::Render"); if (this->textureDirty) { + std::unique_lock 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() / @@ -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 @@ -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(); } ///////////////////////////////////////////////// @@ -2168,10 +2213,11 @@ RenderThread::RenderThread() { RenderWindowItemPrivate::threads << this; qRegisterMetaType(); + qRegisterMetaType("RenderSync*"); } ///////////////////////////////////////////////// -void RenderThread::RenderNext() +void RenderThread::RenderNext(RenderSync *renderSync) { this->context->makeCurrent(this->surface); @@ -2188,7 +2234,7 @@ void RenderThread::RenderNext() return; } - this->ignRenderer.Render(); + this->ignRenderer.Render(renderSync); emit TextureReady(this->ignRenderer.textureId, this->ignRenderer.textureSize); } @@ -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; @@ -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(); @@ -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); } } @@ -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()); diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 3f51fde8dc..9a6025c8c7 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -166,6 +166,45 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { private: std::unique_ptr 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 &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 &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 @@ -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(); @@ -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); @@ -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(); @@ -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; @@ -730,7 +772,7 @@ 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 @@ -738,14 +780,14 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \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); @@ -753,6 +795,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \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; From 29be3014af65761110329e2c1e76a9ab8f64037c Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sat, 24 Apr 2021 16:44:23 -0300 Subject: [PATCH 2/9] Force serialization of render commands This avoids us to break ign-rendering ABI while also simplifying the amount of work to be done Serializing work is easier to maintain and debug Only CPU-bound scenario would potentially benefit from parallel command generation (in terms of UI responsiveness) Parallel command generation can be added back later Also fixed coding style Refer to https://github.com/ignitionrobotics/ign-rendering/issues/304#issuecomment-824130450 for discussion Affects ign-rendering#304 Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 34 +++++++++++++++++++++++------- src/gui/plugins/scene3d/Scene3D.hh | 6 +++--- 2 files changed, 29 insertions(+), 11 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 32515a8280..5639a4baf9 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -449,7 +449,7 @@ using namespace gazebo; QList RenderWindowItemPrivate::threads; ///////////////////////////////////////////////// -void RenderSync::requestQtThreadToBlock(std::unique_lock &lock) +void RenderSync::RequestQtThreadToBlock(std::unique_lock &lock) { this->renderStallState = RenderStallState::WorkerThreadRequested; this->cv.wait(lock, [this] @@ -457,7 +457,7 @@ void RenderSync::requestQtThreadToBlock(std::unique_lock &lock) } ///////////////////////////////////////////////// -void RenderSync::releaseQtThreadFromBlock(std::unique_lock &lock) +void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &lock) { this->renderStallState = RenderStallState::Unblocked; lock.unlock(); @@ -465,7 +465,7 @@ void RenderSync::releaseQtThreadFromBlock(std::unique_lock &lock) } ///////////////////////////////////////////////// -void RenderSync::waitForWorkerThread() +void RenderSync::WaitForWorkerThread() { { std::unique_lock lock(this->mutex); @@ -526,10 +526,20 @@ void IgnRenderer::Render(RenderSync *renderSync) IGN_PROFILE_THREAD_NAME("RenderThread"); IGN_PROFILE("IgnRenderer::Render"); + + std::unique_lock lock(renderSync->mutex); + renderSync->RequestQtThreadToBlock(lock); + if (this->textureDirty) { - std::unique_lock lock(renderSync->mutex); - renderSync->requestQtThreadToBlock(lock); + // TODO(anyone) If SwapFromThread gets implemented, + // then we only need to lock when texture is dirty + // (but we still need to lock the whole routine if + // debugging from RenderDoc or if user is not willing + // to sacrifice VRAM) + // + // std::unique_lock 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() / @@ -540,7 +550,9 @@ void IgnRenderer::Render(RenderSync *renderSync) this->dataPtr->camera->PreRender(); } this->textureDirty = false; - renderSync->releaseQtThreadFromBlock(lock); + + // TODO(anyone) See SwapFromThread comments + // renderSync->ReleaseQtThreadFromBlock(lock); } // texture id could change so get the value in every render update @@ -899,7 +911,13 @@ void IgnRenderer::Render(RenderSync *renderSync) // this notifes ECM to continue updating the scene g_renderCv.notify_one(); - this->dataPtr->camera->SwapFromThread(); + // TODO(anyone) implement a SwapFromThread for parallel command generation + // See https://github.com/ignitionrobotics/ign-rendering/issues/304 + // if( bForcedSerialization ) + // this->dataPtr->camera->SwapFromThread(); + // else + // renderSync->ReleaseQtThreadFromBlock(lock); + renderSync->ReleaseQtThreadFromBlock(lock); } ///////////////////////////////////////////////// @@ -2312,7 +2330,7 @@ void TextureNode::NewTexture(uint _id, const QSize &_size) ///////////////////////////////////////////////// void TextureNode::PrepareNode() { - renderSync.waitForWorkerThread(); + renderSync.WaitForWorkerThread(); this->mutex.lock(); uint newId = this->id; QSize sz = this->size; diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 9a6025c8c7..575504052f 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -197,12 +197,12 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \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 &lock); + public: void RequestQtThreadToBlock(std::unique_lock &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 &lock); + public: void ReleaseQtThreadFromBlock(std::unique_lock &lock); /// \brief Must be called from Qt thread periodically - public: void waitForWorkerThread(); + public: void WaitForWorkerThread(); }; /// \brief Ign-rendering renderer. From 81007581806d281a9b0e430fbf278b7a2000b2df Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Wed, 28 Apr 2021 22:58:40 -0300 Subject: [PATCH 3/9] Fix deadlock on initialization & shutdown Also fixes preexisting race condition when shutting down and improper uninitialization of the worker thread Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 118 +++++++++++++++++++++++++---- src/gui/plugins/scene3d/Scene3D.hh | 45 +---------- 2 files changed, 106 insertions(+), 57 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 5639a4baf9..2c41c9431b 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -368,6 +368,53 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: math::Vector3d scaleSnap = math::Vector3d::One; }; + 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 RequestQtThreadToBlock calls will continue immediately + /// until the first WaitForWorkerThread call is made + Initializing, + /// 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, + /// Same as Unblocked, but RequestQtThreadToBlock and + /// ReleaseQtThreadFromBlock cannot be called + ShuttingDown, + }; + + /// \brief See TextureNode::RenderSync::RenderStallState + public: RenderStallState renderStallState = + RenderStallState::Initializing /*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 &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 &lock); + /// \brief Must be called from Qt thread periodically + public: void WaitForWorkerThread(); + /// \brief Must be called from GUI thread when shutting down + public: void Shutdown(); + }; + /// \brief Private data class for RenderWindowItem class RenderWindowItemPrivate { @@ -377,6 +424,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Render thread public : RenderThread *renderThread = nullptr; + /// \brief See RenderSync + public: RenderSync renderSync; + //// \brief Set to true after the renderer is initialized public: bool rendererInit = false; @@ -451,15 +501,23 @@ QList RenderWindowItemPrivate::threads; ///////////////////////////////////////////////// void RenderSync::RequestQtThreadToBlock(std::unique_lock &lock) { + if (this->renderStallState == RenderStallState::Initializing) + return; + this->renderStallState = RenderStallState::WorkerThreadRequested; this->cv.wait(lock, [this] - { return this->renderStallState == RenderStallState::QtThreadBlocked; }); + { return this->renderStallState == RenderStallState::QtThreadBlocked || + this->renderStallState == RenderStallState::ShuttingDown; }); } ///////////////////////////////////////////////// void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &lock) { - this->renderStallState = RenderStallState::Unblocked; + if (this->renderStallState != RenderStallState::ShuttingDown && + this->renderStallState != RenderStallState::Initializing) + { + this->renderStallState = RenderStallState::Unblocked; + } lock.unlock(); this->cv.notify_one(); } @@ -469,7 +527,11 @@ void RenderSync::WaitForWorkerThread() { { std::unique_lock lock(this->mutex); - if(this->renderStallState == RenderStallState::WorkerThreadRequested) + if(this->renderStallState == RenderStallState::Initializing) + { + this->renderStallState = RenderStallState::Unblocked; + } + else if(this->renderStallState == RenderStallState::WorkerThreadRequested) { // Worker thread asked us to wait! this->renderStallState = RenderStallState::QtThreadBlocked; @@ -482,8 +544,27 @@ void RenderSync::WaitForWorkerThread() { // Wait until we're clear to go std::unique_lock lock(this->mutex); - this->cv.wait(lock, [this] - { return this->renderStallState == RenderStallState::Unblocked; }); + this->cv.wait( lock, [this] + { + return this->renderStallState == RenderStallState::Unblocked || + this->renderStallState == RenderStallState::ShuttingDown; + } ); + } +} + +///////////////////////////////////////////////// +void RenderSync::Shutdown() +{ + { + std::unique_lock lock(this->mutex); + const bool bWakeUpRequested = + this->renderStallState == RenderStallState::WorkerThreadRequested; + this->renderStallState = RenderStallState::ShuttingDown; + if(bWakeUpRequested) + { + lock.unlock(); + this->cv.notify_one(); + } } } @@ -2271,6 +2352,7 @@ void RenderThread::ShutDown() this->surface->deleteLater(); // Stop event processing, move the thread to GUI and make sure it is deleted. + this->exit(); this->moveToThread(QGuiApplication::instance()->thread()); } @@ -2293,8 +2375,8 @@ void RenderThread::SizeChanged() } ///////////////////////////////////////////////// -TextureNode::TextureNode(QQuickWindow *_window) - : window(_window) +TextureNode::TextureNode(QQuickWindow *_window, RenderSync *_renderSync) + : renderSync(_renderSync), window(_window) { // Our texture node must have a texture, so use the default 0 texture. #if QT_VERSION < QT_VERSION_CHECK(5, 14, 0) @@ -2330,7 +2412,7 @@ void TextureNode::NewTexture(uint _id, const QSize &_size) ///////////////////////////////////////////////// void TextureNode::PrepareNode() { - renderSync.WaitForWorkerThread(); + renderSync->WaitForWorkerThread(); this->mutex.lock(); uint newId = this->id; QSize sz = this->size; @@ -2364,7 +2446,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(&this->renderSync); + emit TextureInUse(this->renderSync); } } @@ -2388,7 +2470,15 @@ RenderWindowItem::RenderWindowItem(QQuickItem *_parent) } ///////////////////////////////////////////////// -RenderWindowItem::~RenderWindowItem() = default; +RenderWindowItem::~RenderWindowItem() +{ + this->dataPtr->renderSync.Shutdown(); + QMetaObject::invokeMethod(this->dataPtr->renderThread, + "ShutDown", + Qt::QueuedConnection); + + this->dataPtr->renderThread->wait(); +} ///////////////////////////////////////////////// void RenderWindowItem::Ready() @@ -2411,10 +2501,6 @@ void RenderWindowItem::Ready() this->dataPtr->renderThread->moveToThread(this->dataPtr->renderThread); - this->connect(this, &QObject::destroyed, - this->dataPtr->renderThread, &RenderThread::ShutDown, - Qt::QueuedConnection); - this->connect(this, &QQuickItem::widthChanged, this->dataPtr->renderThread, &RenderThread::SizeChanged); this->connect(this, &QQuickItem::heightChanged, @@ -2477,7 +2563,7 @@ QSGNode *RenderWindowItem::updatePaintNode(QSGNode *_node, if (!node) { - node = new TextureNode(this->window()); + node = new TextureNode(this->window(), &this->dataPtr->renderSync); // Set up connections to get the production of render texture in sync with // vsync on the rendering thread. @@ -2508,7 +2594,7 @@ QSGNode *RenderWindowItem::updatePaintNode(QSGNode *_node, // Get the production of FBO textures started.. QMetaObject::invokeMethod(this->dataPtr->renderThread, "RenderNext", Qt::QueuedConnection, - Q_ARG( RenderSync*, &node->renderSync )); + Q_ARG( RenderSync*, node->renderSync )); } node->setRect(this->boundingRect()); diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 575504052f..a581e4f18c 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -166,44 +166,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { private: std::unique_ptr 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 &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 &lock); - /// \brief Must be called from Qt thread periodically - public: void WaitForWorkerThread(); - }; + class RenderSync; /// \brief Ign-rendering renderer. /// All ign-rendering calls should be performed inside this class as it makes @@ -529,7 +492,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public slots: void RenderNext(RenderSync *renderSync); /// \brief Shutdown the thread and the render engine - public slots: void ShutDown(); + public Q_SLOTS: void ShutDown(); /// \brief Slot called to update render texture size public slots: void SizeChanged(); @@ -763,7 +726,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Constructor /// \param[in] _window Parent window - public: explicit TextureNode(QQuickWindow *_window); + public: explicit TextureNode(QQuickWindow *_window, RenderSync *_renderSync); /// \brief Destructor public: ~TextureNode() override; @@ -796,7 +759,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: QMutex mutex; /// \brief See RenderSync - public: RenderSync renderSync; + public: RenderSync *renderSync; /// \brief Qt's scene graph texture public: QSGTexture *texture = nullptr; From 081e7d0facce62380ed73973c1365829f621b311 Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Fri, 30 Apr 2021 19:45:00 -0300 Subject: [PATCH 4/9] Fix deadlock when using MoveTo modifier Fix coding style Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 38 +++++++++++++++++------------- src/gui/plugins/scene3d/Scene3D.hh | 4 ++-- 2 files changed, 24 insertions(+), 18 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 2c41c9431b..85982b6860 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -405,12 +405,15 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \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 &lock); + public: void RequestQtThreadToBlock(std::unique_lock &_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 &lock); + public: void ReleaseQtThreadFromBlock(std::unique_lock &_lock); + /// \brief Must be called from Qt thread periodically public: void WaitForWorkerThread(); + /// \brief Must be called from GUI thread when shutting down public: void Shutdown(); }; @@ -499,26 +502,26 @@ using namespace gazebo; QList RenderWindowItemPrivate::threads; ///////////////////////////////////////////////// -void RenderSync::RequestQtThreadToBlock(std::unique_lock &lock) +void RenderSync::RequestQtThreadToBlock(std::unique_lock &_lock) { if (this->renderStallState == RenderStallState::Initializing) return; this->renderStallState = RenderStallState::WorkerThreadRequested; - this->cv.wait(lock, [this] + this->cv.wait(_lock, [this] { return this->renderStallState == RenderStallState::QtThreadBlocked || this->renderStallState == RenderStallState::ShuttingDown; }); } ///////////////////////////////////////////////// -void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &lock) +void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &_lock) { if (this->renderStallState != RenderStallState::ShuttingDown && this->renderStallState != RenderStallState::Initializing) { this->renderStallState = RenderStallState::Unblocked; } - lock.unlock(); + _lock.unlock(); this->cv.notify_one(); } @@ -593,7 +596,7 @@ RenderUtil *IgnRenderer::RenderUtil() const } ///////////////////////////////////////////////// -void IgnRenderer::Render(RenderSync *renderSync) +void IgnRenderer::Render(RenderSync *_renderSync) { rendering::ScenePtr scene = this->dataPtr->renderUtil.Scene(); if (!scene) @@ -608,8 +611,8 @@ void IgnRenderer::Render(RenderSync *renderSync) IGN_PROFILE_THREAD_NAME("RenderThread"); IGN_PROFILE("IgnRenderer::Render"); - std::unique_lock lock(renderSync->mutex); - renderSync->RequestQtThreadToBlock(lock); + std::unique_lock lock(_renderSync->mutex); + _renderSync->RequestQtThreadToBlock(lock); if (this->textureDirty) { @@ -620,7 +623,7 @@ void IgnRenderer::Render(RenderSync *renderSync) // to sacrifice VRAM) // // std::unique_lock lock(renderSync->mutex); - // renderSync->RequestQtThreadToBlock(lock); + // _renderSync->RequestQtThreadToBlock(lock); this->dataPtr->camera->SetImageWidth(this->textureSize.width()); this->dataPtr->camera->SetImageHeight(this->textureSize.height()); this->dataPtr->camera->SetAspectRatio(this->textureSize.width() / @@ -633,7 +636,7 @@ void IgnRenderer::Render(RenderSync *renderSync) this->textureDirty = false; // TODO(anyone) See SwapFromThread comments - // renderSync->ReleaseQtThreadFromBlock(lock); + // _renderSync->ReleaseQtThreadFromBlock(lock); } // texture id could change so get the value in every render update @@ -823,7 +826,10 @@ void IgnRenderer::Render(RenderSync *renderSync) { IGN_PROFILE("IgnRenderer::Render Follow"); if (!this->dataPtr->moveToTarget.empty()) + { + _renderSync->ReleaseQtThreadFromBlock(lock); return; + } rendering::NodePtr followTarget = this->dataPtr->camera->FollowTarget(); if (!this->dataPtr->followTarget.empty()) { @@ -997,8 +1003,8 @@ void IgnRenderer::Render(RenderSync *renderSync) // if( bForcedSerialization ) // this->dataPtr->camera->SwapFromThread(); // else - // renderSync->ReleaseQtThreadFromBlock(lock); - renderSync->ReleaseQtThreadFromBlock(lock); + // _renderSync->ReleaseQtThreadFromBlock(lock); + _renderSync->ReleaseQtThreadFromBlock(lock); } ///////////////////////////////////////////////// @@ -2316,7 +2322,7 @@ RenderThread::RenderThread() } ///////////////////////////////////////////////// -void RenderThread::RenderNext(RenderSync *renderSync) +void RenderThread::RenderNext(RenderSync *_renderSync) { this->context->makeCurrent(this->surface); @@ -2333,7 +2339,7 @@ void RenderThread::RenderNext(RenderSync *renderSync) return; } - this->ignRenderer.Render(renderSync); + this->ignRenderer.Render(_renderSync); emit TextureReady(this->ignRenderer.textureId, this->ignRenderer.textureSize); } @@ -2412,7 +2418,7 @@ void TextureNode::NewTexture(uint _id, const QSize &_size) ///////////////////////////////////////////////// void TextureNode::PrepareNode() { - renderSync->WaitForWorkerThread(); + this->renderSync->WaitForWorkerThread(); this->mutex.lock(); uint newId = this->id; QSize sz = this->size; diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index a581e4f18c..e8b4eca637 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -185,7 +185,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: ~IgnRenderer() override; /// \brief Main render function - public: void Render(RenderSync *renderSync); + public: void Render(RenderSync *_renderSync); /// \brief Initialize the render engine public: void Initialize(); @@ -743,7 +743,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Signal emitted when the texture is being rendered and renderer /// can start rendering next frame - signals: void TextureInUse(RenderSync *renderSync); + signals: void TextureInUse(RenderSync *_renderSync); /// \brief Signal emitted when a new texture is ready to trigger window /// update From c236828402459013b237dfab642d802cce897822 Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 9 May 2021 14:24:10 -0300 Subject: [PATCH 5/9] Reimplemented synchronization mechanism to fix deadlocks It's a good thing we went for serializing rendering. THe way Qt implements the double buffer scheme using signals & slots is fundamentally flawed because it assumes the worker thread never needs to synchronize (e.g. to invalidate FBOs if window resolution changes). Trying to synchronize can easily cause deadlocks if Qt thread has spurious updates which don't end up emitting TextureInUse, as the worker thread is running slower than Qt thread. A way to fix this could be to use a different synchronization mechanism where the main thread increases a request counter and the worker thread is constantly looping but only wakes up when that counter is > 0. For now, this will do. Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 115 ++++++++++++++--------------- 1 file changed, 56 insertions(+), 59 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 85982b6860..1d58c8b8df 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -382,30 +382,27 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: enum class RenderStallState { - /// All RequestQtThreadToBlock calls will continue immediately - /// until the first WaitForWorkerThread call is made - Initializing, - /// 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, - /// Same as Unblocked, but RequestQtThreadToBlock and - /// ReleaseQtThreadFromBlock cannot be called + /// Qt is stuck inside WaitForWorkerThread + /// Worker thread can proceed + WorkerCanProceed, + /// Qt is stuck inside WaitForWorkerThread + /// Worker thread is between WaitForQtThreadAndBlock + /// and ReleaseQtThreadFromBlock + WorkerIsProceeding, + /// Worker is stuck inside WaitForQtThreadAndBlock + /// Qt can proceed + QtCanProceed, + /// Do not block ShuttingDown, }; /// \brief See TextureNode::RenderSync::RenderStallState public: RenderStallState renderStallState = - RenderStallState::Initializing /*GUARDED_BY(sharedRenderMutex)*/; + RenderStallState::QtCanProceed /*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 &_lock); + public: void WaitForQtThreadAndBlock(std::unique_lock &_lock); /// \brief Must be called from worker thread when we are done /// \param[in] lock Acquired lock. Must be based on this->mutex @@ -502,25 +499,19 @@ using namespace gazebo; QList RenderWindowItemPrivate::threads; ///////////////////////////////////////////////// -void RenderSync::RequestQtThreadToBlock(std::unique_lock &_lock) +void RenderSync::WaitForQtThreadAndBlock(std::unique_lock &_lock) { - if (this->renderStallState == RenderStallState::Initializing) - return; - - this->renderStallState = RenderStallState::WorkerThreadRequested; this->cv.wait(_lock, [this] - { return this->renderStallState == RenderStallState::QtThreadBlocked || + { return this->renderStallState == RenderStallState::WorkerCanProceed || this->renderStallState == RenderStallState::ShuttingDown; }); + + this->renderStallState = RenderStallState::WorkerIsProceeding; } ///////////////////////////////////////////////// void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &_lock) { - if (this->renderStallState != RenderStallState::ShuttingDown && - this->renderStallState != RenderStallState::Initializing) - { - this->renderStallState = RenderStallState::Unblocked; - } + this->renderStallState = RenderStallState::QtCanProceed; _lock.unlock(); this->cv.notify_one(); } @@ -528,31 +519,28 @@ void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock &_lock) ///////////////////////////////////////////////// void RenderSync::WaitForWorkerThread() { + std::unique_lock lock(this->mutex); + + // Wait until we're clear to go + this->cv.wait( lock, [this] { - std::unique_lock lock(this->mutex); - if(this->renderStallState == RenderStallState::Initializing) - { - this->renderStallState = RenderStallState::Unblocked; - } - else 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(); - } - } + return this->renderStallState == RenderStallState::QtCanProceed || + this->renderStallState == RenderStallState::ShuttingDown; + } ); + + // Worker thread asked us to wait! + this->renderStallState = RenderStallState::WorkerCanProceed; + lock.unlock(); + // Wake up worker thread + this->cv.notify_one(); + lock.lock(); + // Wait until we're clear to go + this->cv.wait( lock, [this] { - // Wait until we're clear to go - std::unique_lock lock(this->mutex); - this->cv.wait( lock, [this] - { - return this->renderStallState == RenderStallState::Unblocked || - this->renderStallState == RenderStallState::ShuttingDown; - } ); - } + return this->renderStallState == RenderStallState::QtCanProceed || + this->renderStallState == RenderStallState::ShuttingDown; + } ); } ///////////////////////////////////////////////// @@ -560,14 +548,11 @@ void RenderSync::Shutdown() { { std::unique_lock lock(this->mutex); - const bool bWakeUpRequested = - this->renderStallState == RenderStallState::WorkerThreadRequested; + this->renderStallState = RenderStallState::ShuttingDown; - if(bWakeUpRequested) - { - lock.unlock(); - this->cv.notify_one(); - } + + lock.unlock(); + this->cv.notify_one(); } } @@ -612,7 +597,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) IGN_PROFILE("IgnRenderer::Render"); std::unique_lock lock(_renderSync->mutex); - _renderSync->RequestQtThreadToBlock(lock); + _renderSync->WaitForQtThreadAndBlock(lock); if (this->textureDirty) { @@ -623,7 +608,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) // to sacrifice VRAM) // // std::unique_lock lock(renderSync->mutex); - // _renderSync->RequestQtThreadToBlock(lock); + // _renderSync->WaitForQtThreadAndBlock(lock); this->dataPtr->camera->SetImageWidth(this->textureSize.width()); this->dataPtr->camera->SetImageHeight(this->textureSize.height()); this->dataPtr->camera->SetAspectRatio(this->textureSize.width() / @@ -2418,7 +2403,6 @@ void TextureNode::NewTexture(uint _id, const QSize &_size) ///////////////////////////////////////////////// void TextureNode::PrepareNode() { - this->renderSync->WaitForWorkerThread(); this->mutex.lock(); uint newId = this->id; QSize sz = this->size; @@ -2454,6 +2438,19 @@ void TextureNode::PrepareNode() // rendered and it can start rendering to the other one. emit TextureInUse(this->renderSync); } + else + { + // This is necessary because we're forcing serialization of + // of worker and Qt threads via renderSync; and if PrepareNode gets + // called twice in a row with the worker thread still finishing the + // 1st iteration, it may result in a deadlock for newer versions of Qt; + // as WaitForWorkerThread will be called with no corresponding + // WaitForQtThreadAndBlock as the worker thread thinks there is + // no more jobs to do. + emit TextureInUse(this->renderSync); + } + + this->renderSync->WaitForWorkerThread(); } ///////////////////////////////////////////////// From e1583bad992d1643f6925624013c69c85e2425ca Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Mon, 10 May 2021 16:02:17 -0300 Subject: [PATCH 6/9] Document RenderSync Turn some pointers into references Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 48 ++++++++++++++++++++++++++---- src/gui/plugins/scene3d/Scene3D.hh | 5 ++-- 2 files changed, 45 insertions(+), 8 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 1d58c8b8df..239ad45776 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -368,6 +368,42 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: math::Vector3d scaleSnap = math::Vector3d::One; }; + /// \brief Qt and Ogre rendering is happening in different threads + /// The original sample 'textureinthread' from Qt used a double-buffer + /// scheme so that the worker (Ogre) thread write to FBO A, while + /// Qt is displaying FBO B. + /// + /// However Qt's implementation doesn't handle all the edge cases + /// (like resizing a window), and also it increases our VRAM + /// consumption in multiple ways (since we have to double other + /// resources as well or re-architect certain parts of the code + /// to avoid it) + /// + /// Thus we just serialize both threads so that when Qt reaches + /// drawing preparation, it halts and Ogre worker thread starts rendering, + /// then resumes when Ogre is done. + /// + /// This code is admitedly more complicated than it should be + /// because Qt's synchronization using signals and slots causes + /// deadlocks when other means of synchronization are introduced. + /// The whole threaded loop should be rewritten. + /// + /// All RenderSync does is conceptually: + /// + /// \code + /// TextureNode::PrepareNode() + /// { + /// renderSync.WaitForWorkerThread(); // Qt thread + /// // WaitForQtThreadAndBlock(); + /// // Now worker thread begins executing what's between + /// // ReleaseQtThreadFromBlock(); + /// continue with qt code... + /// } + /// \endcode + /// + /// + /// For more info see + /// https://github.com/ignitionrobotics/ign-rendering/issues/304 class RenderSync { /// \brief Cond. variable to synchronize rendering on specific events @@ -2366,7 +2402,7 @@ void RenderThread::SizeChanged() } ///////////////////////////////////////////////// -TextureNode::TextureNode(QQuickWindow *_window, RenderSync *_renderSync) +TextureNode::TextureNode(QQuickWindow *_window, RenderSync &_renderSync) : renderSync(_renderSync), window(_window) { // Our texture node must have a texture, so use the default 0 texture. @@ -2436,7 +2472,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(this->renderSync); + emit TextureInUse(&this->renderSync); } else { @@ -2447,10 +2483,10 @@ void TextureNode::PrepareNode() // as WaitForWorkerThread will be called with no corresponding // WaitForQtThreadAndBlock as the worker thread thinks there is // no more jobs to do. - emit TextureInUse(this->renderSync); + emit TextureInUse(&this->renderSync); } - this->renderSync->WaitForWorkerThread(); + this->renderSync.WaitForWorkerThread(); } ///////////////////////////////////////////////// @@ -2566,7 +2602,7 @@ QSGNode *RenderWindowItem::updatePaintNode(QSGNode *_node, if (!node) { - node = new TextureNode(this->window(), &this->dataPtr->renderSync); + node = new TextureNode(this->window(), this->dataPtr->renderSync); // Set up connections to get the production of render texture in sync with // vsync on the rendering thread. @@ -2597,7 +2633,7 @@ QSGNode *RenderWindowItem::updatePaintNode(QSGNode *_node, // Get the production of FBO textures started.. QMetaObject::invokeMethod(this->dataPtr->renderThread, "RenderNext", Qt::QueuedConnection, - Q_ARG( RenderSync*, node->renderSync )); + Q_ARG( RenderSync*, &node->renderSync )); } node->setRect(this->boundingRect()); diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index e8b4eca637..8defaa5512 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -726,7 +726,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Constructor /// \param[in] _window Parent window - public: explicit TextureNode(QQuickWindow *_window, RenderSync *_renderSync); + public: explicit TextureNode(QQuickWindow *_window, + RenderSync &_renderSync); /// \brief Destructor public: ~TextureNode() override; @@ -759,7 +760,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: QMutex mutex; /// \brief See RenderSync - public: RenderSync *renderSync; + public: RenderSync &renderSync; /// \brief Qt's scene graph texture public: QSGTexture *texture = nullptr; From d55468d17702ee18df2106a66a99d073987c6e8f Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sat, 15 May 2021 12:17:24 -0300 Subject: [PATCH 7/9] Document missing parameter Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.hh | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 8defaa5512..bf7639bd05 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -185,6 +185,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: ~IgnRenderer() override; /// \brief Main render function + /// \param[in] _renderSync RenderSync to safely + /// synchronize Qt and worker thread (this) public: void Render(RenderSync *_renderSync); /// \brief Initialize the render engine @@ -489,6 +491,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: RenderThread(); /// \brief Render the next frame + /// \param[in] _renderSync RenderSync to safely + /// synchronize Qt and worker thread (this) public slots: void RenderNext(RenderSync *renderSync); /// \brief Shutdown the thread and the render engine @@ -726,6 +730,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Constructor /// \param[in] _window Parent window + /// \param[in] _renderSync RenderSync to safely + /// synchronize Qt (this) and worker thread public: explicit TextureNode(QQuickWindow *_window, RenderSync &_renderSync); @@ -744,6 +750,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Signal emitted when the texture is being rendered and renderer /// can start rendering next frame + /// \param[in] _renderSync RenderSync to send to the worker thread signals: void TextureInUse(RenderSync *_renderSync); /// \brief Signal emitted when a new texture is ready to trigger window From 55b2a7ebb1717219d58f28a88fae872b90f68f65 Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 23 May 2021 17:29:07 -0300 Subject: [PATCH 8/9] Document better our use of emit TextureInUse Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.cc | 35 ++++++++++++++++++++---------- 1 file changed, 23 insertions(+), 12 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 239ad45776..ed8a1f4068 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2472,20 +2472,31 @@ 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(&this->renderSync); - } - else - { - // This is necessary because we're forcing serialization of - // of worker and Qt threads via renderSync; and if PrepareNode gets - // called twice in a row with the worker thread still finishing the - // 1st iteration, it may result in a deadlock for newer versions of Qt; - // as WaitForWorkerThread will be called with no corresponding - // WaitForQtThreadAndBlock as the worker thread thinks there is - // no more jobs to do. - emit TextureInUse(&this->renderSync); + // emit TextureInUse(&this->renderSync); See comment below } + // NOTE: The original code from Qt samples only emitted when + // newId is not null. + // + // This is correct... for their case. + // However we need to synchronize the threads when resolution changes, + // and we're also currently doing everything in lockstep (i.e. both Qt + // and worker thread are serialized, + // see https://github.com/ignitionrobotics/ign-rendering/issues/304 ) + // + // We need to emit even if newId == 0 because it's safe as long as both + // threads are forcefully serialized and otherwise we may get a + // deadlock (this func. called twice in a row with the worker thread still + // finishing the 1st iteration, may result in a deadlock for newer versions + // of Qt; as WaitForWorkerThread will be called with no corresponding + // WaitForQtThreadAndBlock as the worker thread thinks there are + // no more jobs to do. + // + // If we want these to run in worker thread and stay resolution-synchronized, + // we probably should use a different method of signals and slots + // to send work to the worker thread and get results back + emit TextureInUse(&this->renderSync); + this->renderSync.WaitForWorkerThread(); } From 6285e23383eaa4209c004e866b33e9960ebd0d14 Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 23 May 2021 17:34:05 -0300 Subject: [PATCH 9/9] Change Q_SLOTS to slots for consistency I changed it because it didn't work, but it must've been old code because it works now. Signed-off-by: Matias N. Goldberg --- src/gui/plugins/scene3d/Scene3D.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index bf7639bd05..ff510dd71b 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -496,7 +496,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public slots: void RenderNext(RenderSync *renderSync); /// \brief Shutdown the thread and the render engine - public Q_SLOTS: void ShutDown(); + public slots: void ShutDown(); /// \brief Slot called to update render texture size public slots: void SizeChanged();