From 040b88a693f6cd7f326dadd038cbdf70dc35b324 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 13 Dec 2024 00:32:09 +0100 Subject: [PATCH 1/3] Make panda framework static, so that its lifetime is tied to the program and multiple renderers can be attached to it --- .../include/visp3/ar/vpPanda3DBaseRenderer.h | 9 +++--- .../include/visp3/ar/vpPanda3DRendererSet.h | 2 +- .../vpPanda3DBaseRenderer.cpp | 28 +++++++++++-------- .../vpPanda3DRendererSet.cpp | 26 ++++++++--------- 4 files changed, 35 insertions(+), 30 deletions(-) diff --git a/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h b/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h index d0844a4625..8883a29901 100644 --- a/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h +++ b/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h @@ -58,7 +58,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer { public: vpPanda3DBaseRenderer(const std::string &rendererName) - : m_name(rendererName), m_renderOrder(-100), m_framework(nullptr), m_window(nullptr), m_camera(nullptr) + : m_name(rendererName), m_renderOrder(-100), m_window(nullptr), m_camera(nullptr) { setVerticalSyncEnabled(false); } @@ -71,7 +71,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer * Will also perform the renderer setup (scene, camera and render targets) */ virtual void initFramework(); - virtual void initFromParent(std::shared_ptr framework, PointerTo window); + virtual void initFromParent(PointerTo window); virtual void initFromParent(const vpPanda3DBaseRenderer &renderer); virtual void beforeFrameRendered() { } @@ -80,7 +80,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer { GraphicsOutput *mainBuffer = getMainOutputBuffer(); if (mainBuffer != nullptr) { - m_framework->get_graphics_engine()->extract_texture_data(mainBuffer->get_texture(), mainBuffer->get_gsg()); + m_window->get_graphics_output()->get_engine()->extract_texture_data(mainBuffer->get_texture(), mainBuffer->get_gsg()); } } @@ -266,11 +266,12 @@ class VISP_EXPORT vpPanda3DBaseRenderer const static vpHomogeneousMatrix VISP_T_PANDA; //! Homogeneous transformation matrix to convert from the Panda coordinate system (right-handed Z-up) to the ViSP coordinate system (right-handed Y-Down) const static vpHomogeneousMatrix PANDA_T_VISP; //! Inverse of VISP_T_PANDA + static PandaFramework framework; //! Panda Rendering framework + static bool frameworkIsOpen; protected: std::string m_name; //! name of the renderer int m_renderOrder; //! Rendering priority for this renderer and its buffers. A lower value will be rendered first. Should be used when calling make_output in setupRenderTarget() - std::shared_ptr m_framework; //! Pointer to the active panda framework PointerTo m_window; //! Pointer to owning window, which can create buffers etc. It is not necessarily visible. vpPanda3DRenderParameters m_renderParameters; //! Rendering parameters NodePath m_renderRoot; //! Node containing all the objects and the camera for this renderer diff --git a/modules/ar/include/visp3/ar/vpPanda3DRendererSet.h b/modules/ar/include/visp3/ar/vpPanda3DRendererSet.h index 49098952cf..e3679e4468 100644 --- a/modules/ar/include/visp3/ar/vpPanda3DRendererSet.h +++ b/modules/ar/include/visp3/ar/vpPanda3DRendererSet.h @@ -71,7 +71,7 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp * Thus, if a renderer B depends on A for its render, and if B.getRenderOrder() > A.getRenderOrder() it can rely on A being initialized when B.initFromParent is called (along with the setupCamera, setupRenderTarget). */ void initFramework() VP_OVERRIDE; - void initFromParent(std::shared_ptr framework, PointerTo window) VP_OVERRIDE; + void initFromParent(PointerTo window) VP_OVERRIDE; void initFromParent(const vpPanda3DBaseRenderer &renderer) VP_OVERRIDE; /** diff --git a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp index 734a00b6b9..f8caa74ed7 100644 --- a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp +++ b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp @@ -48,22 +48,27 @@ const vpHomogeneousMatrix vpPanda3DBaseRenderer::VISP_T_PANDA({ }); const vpHomogeneousMatrix vpPanda3DBaseRenderer::PANDA_T_VISP(vpPanda3DBaseRenderer::VISP_T_PANDA.inverse()); + +PandaFramework vpPanda3DBaseRenderer::framework; +bool vpPanda3DBaseRenderer::frameworkIsOpen(false); + + void vpPanda3DBaseRenderer::initFramework() { - if (m_framework.use_count() > 0) { - throw vpException(vpException::notImplementedError, - "Panda3D renderer: Reinitializing is not supported!"); + + if (!frameworkIsOpen) { + frameworkIsOpen = true; + framework.open_framework(); } - m_framework = std::shared_ptr(new PandaFramework()); - m_framework->open_framework(); + WindowProperties winProps; winProps.set_size(LVecBase2i(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight())); int flags = GraphicsPipe::BF_refuse_window; - m_window = m_framework->open_window(winProps, flags); + m_window = framework.open_window(winProps, flags); // try and reopen with visible window if (m_window == nullptr) { winProps.set_minimized(true); - m_window = m_framework->open_window(winProps, 0); + m_window = framework.open_window(winProps, 0); } if (m_window == nullptr) { throw vpException(vpException::notInitialized, @@ -76,9 +81,8 @@ void vpPanda3DBaseRenderer::initFramework() //m_window->get_display_region_3d()->set_camera(m_cameraPath); } -void vpPanda3DBaseRenderer::initFromParent(std::shared_ptr framework, PointerTo window) +void vpPanda3DBaseRenderer::initFromParent(PointerTo window) { - m_framework = framework; m_window = window; setupScene(); setupCamera(); @@ -87,7 +91,7 @@ void vpPanda3DBaseRenderer::initFromParent(std::shared_ptr frame void vpPanda3DBaseRenderer::initFromParent(const vpPanda3DBaseRenderer &renderer) { - initFromParent(renderer.m_framework, renderer.m_window); + initFromParent(renderer.m_window); } void vpPanda3DBaseRenderer::setupScene() @@ -109,7 +113,7 @@ void vpPanda3DBaseRenderer::setupCamera() void vpPanda3DBaseRenderer::renderFrame() { beforeFrameRendered(); - m_framework->get_graphics_engine()->render_frame(); + m_window->get_graphics_output()->get_engine()->render_frame(); afterFrameRendered(); } @@ -273,7 +277,7 @@ void vpPanda3DBaseRenderer::enableSharedDepthBuffer(vpPanda3DBaseRenderer &sourc NodePath vpPanda3DBaseRenderer::loadObject(const std::string &nodeName, const std::string &modelPath) { - NodePath model = m_window->load_model(m_framework->get_models(), modelPath); + NodePath model = m_window->load_model(framework.get_models(), modelPath); for (int i = 0; i < model.get_num_children(); ++i) { model.get_child(i).clear_transform(); } diff --git a/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp b/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp index a9730e0f90..eb899f2a8c 100644 --- a/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp +++ b/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp @@ -45,19 +45,19 @@ vpPanda3DRendererSet::vpPanda3DRendererSet(const vpPanda3DRenderParameters &rend void vpPanda3DRendererSet::initFramework() { - if (m_framework.use_count() > 0) { - throw vpException(vpException::notImplementedError, "Panda3D renderer: Reinitializing is not supported!"); + + if (!frameworkIsOpen) { + frameworkIsOpen = true; + framework.open_framework(); } - m_framework = std::shared_ptr(new PandaFramework()); - m_framework->open_framework(); WindowProperties winProps; winProps.set_size(LVecBase2i(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight())); int flags = GraphicsPipe::BF_refuse_window; - m_window = m_framework->open_window(winProps, flags); + m_window = framework.open_window(winProps, flags); if (m_window == nullptr) { winProps.set_minimized(true); - m_window = m_framework->open_window(winProps, 0); + m_window = framework.open_window(winProps, 0); } if (m_window == nullptr) { throw vpException(vpException::fatalError, "Could not open Panda3D window (hidden or visible)"); @@ -65,15 +65,15 @@ void vpPanda3DRendererSet::initFramework() m_window->set_background_type(WindowFramework::BackgroundType::BT_black); for (std::shared_ptr &renderer: m_subRenderers) { - renderer->initFromParent(m_framework, m_window); + renderer->initFromParent(*this); } } -void vpPanda3DRendererSet::initFromParent(std::shared_ptr framework, PointerTo window) +void vpPanda3DRendererSet::initFromParent(PointerTo window) { - vpPanda3DBaseRenderer::initFromParent(framework, window); + vpPanda3DBaseRenderer::initFromParent(window); for (std::shared_ptr &renderer: m_subRenderers) { - renderer->initFromParent(m_framework, m_window); + renderer->initFromParent(m_window); } } @@ -177,12 +177,12 @@ void vpPanda3DRendererSet::addSubRenderer(std::shared_ptr ++it; } m_subRenderers.insert(it, renderer); - renderer->setRenderParameters(m_renderParameters); - if (m_framework != nullptr) { - renderer->initFromParent(m_framework, m_window); + if (m_window != nullptr) { + renderer->initFromParent(m_window); renderer->setCameraPose(getCameraPose()); } + } void vpPanda3DRendererSet::enableSharedDepthBuffer(vpPanda3DBaseRenderer &sourceBuffer) From 4559f93071639e4f12a9190e2c53349fccd6a7d6 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 13 Dec 2024 16:42:31 +0100 Subject: [PATCH 2/3] correctly clear windows on exit to avoid panda assert --- modules/ar/CMakeLists.txt | 12 +++ .../include/visp3/ar/vpPanda3DBaseRenderer.h | 17 +++- .../vpPanda3DBaseRenderer.cpp | 4 + .../vpPanda3DRendererSet.cpp | 1 + modules/ar/test/catchPanda.cpp | 89 +++++++++++++++++++ 5 files changed, 121 insertions(+), 2 deletions(-) create mode 100644 modules/ar/test/catchPanda.cpp diff --git a/modules/ar/CMakeLists.txt b/modules/ar/CMakeLists.txt index 15c70e9c76..e631b8df34 100644 --- a/modules/ar/CMakeLists.txt +++ b/modules/ar/CMakeLists.txt @@ -191,3 +191,15 @@ vp_glob_module_sources() vp_module_include_directories(${opt_incs} SYSTEM ${opt_system_incs}) vp_create_module(${opt_libs}) + + +set(opt_test_incs "") +set(opt_test_libs "") + +if(WITH_CATCH2) + # catch2 is private + list(APPEND opt_test_incs ${CATCH2_INCLUDE_DIRS}) + list(APPEND opt_test_libs ${CATCH2_LIBRARIES}) +endif() + +vp_add_tests(DEPENDS_ON visp_core PRIVATE_INCLUDE_DIRS ${opt_test_incs} PRIVATE_LIBRARIES ${opt_test_libs}) diff --git a/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h b/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h index 8883a29901..209c92830f 100644 --- a/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h +++ b/modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h @@ -58,12 +58,24 @@ class VISP_EXPORT vpPanda3DBaseRenderer { public: vpPanda3DBaseRenderer(const std::string &rendererName) - : m_name(rendererName), m_renderOrder(-100), m_window(nullptr), m_camera(nullptr) + : m_name(rendererName), m_renderOrder(-100), m_window(nullptr), m_camera(nullptr), m_isWindowOwner(false) { setVerticalSyncEnabled(false); } - virtual ~vpPanda3DBaseRenderer() = default; + virtual ~vpPanda3DBaseRenderer() + { + if (m_window != nullptr) { + for (GraphicsOutput *buffer: m_buffers) { + buffer->get_engine()->remove_window(buffer); + } + } + if (m_isWindowOwner) { + framework.close_window(m_window); + } + + m_window = nullptr; + } /** * @brief Initialize the whole Panda3D framework. Create a new PandaFramework object and a new window. @@ -278,6 +290,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer PointerTo m_camera; NodePath m_cameraPath; //! NodePath of the camera std::vector m_buffers; //! Set of buffers that this renderer uses. This storage contains weak refs to those buffers and should not deallocate them. + bool m_isWindowOwner; // Whether this panda subrenderer is the "owner" of the window framework and should close all associated windows when getting destroyed }; END_VISP_NAMESPACE diff --git a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp index f8caa74ed7..73cbc40dc9 100644 --- a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp +++ b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp @@ -61,6 +61,8 @@ void vpPanda3DBaseRenderer::initFramework() framework.open_framework(); } + m_isWindowOwner = true; + WindowProperties winProps; winProps.set_size(LVecBase2i(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight())); int flags = GraphicsPipe::BF_refuse_window; @@ -83,6 +85,7 @@ void vpPanda3DBaseRenderer::initFramework() void vpPanda3DBaseRenderer::initFromParent(PointerTo window) { + m_isWindowOwner = false; m_window = window; setupScene(); setupCamera(); @@ -91,6 +94,7 @@ void vpPanda3DBaseRenderer::initFromParent(PointerTo window) void vpPanda3DBaseRenderer::initFromParent(const vpPanda3DBaseRenderer &renderer) { + m_isWindowOwner = false; initFromParent(renderer.m_window); } diff --git a/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp b/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp index eb899f2a8c..8051a7b4f3 100644 --- a/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp +++ b/modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp @@ -50,6 +50,7 @@ void vpPanda3DRendererSet::initFramework() frameworkIsOpen = true; framework.open_framework(); } + m_isWindowOwner = true; WindowProperties winProps; winProps.set_size(LVecBase2i(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight())); diff --git a/modules/ar/test/catchPanda.cpp b/modules/ar/test/catchPanda.cpp new file mode 100644 index 0000000000..3b3b3f232a --- /dev/null +++ b/modules/ar/test/catchPanda.cpp @@ -0,0 +1,89 @@ +/* + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * + * Description: + * Test vpCameraParameters JSON parse / save. + */ + +/*! + \example catchJsonCamera.cpp + + Test saving and parsing JSON configuration for vpCameraParameters. +*/ + +#include +#include + +#if defined(VISP_HAVE_PANDA3D) && defined(VISP_HAVE_CATCH2) +#include +#include +#include +#include +#include + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + +#include + +SCENARIO("Instanciating multiple Panda3D renderers", "[Panda3D]") +{ + GIVEN("A single renderer") + { + vpCameraParameters cam(600, 600, 160, 120); + vpPanda3DRenderParameters renderParams(cam, 240, 320, 0.001, 1.0); + vpPanda3DGeometryRenderer r1(vpPanda3DGeometryRenderer::CAMERA_NORMALS); + r1.setRenderParameters(renderParams); + r1.initFramework(); + + WHEN("Creating another, uncoupled renderer") + { + // vpPanda3DGeometryRenderer r2(vpPanda3DGeometryRenderer::CAMERA_NORMALS); + // r2.setRenderParameters(renderParams); + // r2.initFramework(); + + } + } +} + +int main(int argc, char *argv[]) +{ + Catch::Session session; // There must be exactly one instance + session.applyCommandLine(argc, argv); + + int numFailed = session.run(); + return numFailed; +} + +#else + +int main() { return EXIT_SUCCESS; } + +#endif From a0ba03b8c17142bdad432309870a93613c80c8d1 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 13 Dec 2024 16:59:01 +0100 Subject: [PATCH 3/3] Disable rendering for the other renderers for which renderFrame was not called (done by disabling the gsg) --- .../vpPanda3DBaseRenderer.cpp | 11 ++++++++++ modules/ar/test/catchPanda.cpp | 20 +++++++++++-------- 2 files changed, 23 insertions(+), 8 deletions(-) diff --git a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp index 73cbc40dc9..75ae0cce59 100644 --- a/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp +++ b/modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp @@ -117,7 +117,18 @@ void vpPanda3DBaseRenderer::setupCamera() void vpPanda3DBaseRenderer::renderFrame() { beforeFrameRendered(); + // Disable rendering for all the other renderers + for (int i = 0; i < framework.get_num_windows(); ++i) { + WindowFramework *fi = framework.get_window(i); + if (fi != m_window) { + fi->get_graphics_output()->get_gsg()->set_active(false); + } + } m_window->get_graphics_output()->get_engine()->render_frame(); + for (int i = 0; i < framework.get_num_windows(); ++i) { + WindowFramework *fi = framework.get_window(i); + fi->get_graphics_output()->get_gsg()->set_active(true); + } afterFrameRendered(); } diff --git a/modules/ar/test/catchPanda.cpp b/modules/ar/test/catchPanda.cpp index 3b3b3f232a..697b25b103 100644 --- a/modules/ar/test/catchPanda.cpp +++ b/modules/ar/test/catchPanda.cpp @@ -53,22 +53,26 @@ using namespace VISP_NAMESPACE_NAME; #include + +vpPanda3DRenderParameters defaultRenderParams() +{ + vpCameraParameters cam(600, 600, 160, 120); + return vpPanda3DRenderParameters(cam, 240, 320, 0.001, 1.0); +} + SCENARIO("Instanciating multiple Panda3D renderers", "[Panda3D]") { GIVEN("A single renderer") { - vpCameraParameters cam(600, 600, 160, 120); - vpPanda3DRenderParameters renderParams(cam, 240, 320, 0.001, 1.0); vpPanda3DGeometryRenderer r1(vpPanda3DGeometryRenderer::CAMERA_NORMALS); - r1.setRenderParameters(renderParams); + r1.setRenderParameters(defaultRenderParams()); r1.initFramework(); - WHEN("Creating another, uncoupled renderer") + THEN("Creating another, uncoupled renderer is ok and its destruction does not raise an error") { - // vpPanda3DGeometryRenderer r2(vpPanda3DGeometryRenderer::CAMERA_NORMALS); - // r2.setRenderParameters(renderParams); - // r2.initFramework(); - + vpPanda3DGeometryRenderer r2(vpPanda3DGeometryRenderer::CAMERA_NORMALS); + r2.setRenderParameters(defaultRenderParams()); + r2.initFramework(); } } }