Visual Servoing Platform  version 3.6.1 under development (2024-09-08)
vpPanda3DRendererSet Class Reference

#include <visp3/ar/vpPanda3DRendererSet.h>

+ Inheritance diagram for vpPanda3DRendererSet:

Public Member Functions

 vpPanda3DRendererSet (const vpPanda3DRenderParameters &renderParameters)
 
virtual ~vpPanda3DRendererSet ()=default
 
void initFramework () VP_OVERRIDE
 
void initFromParent (std::shared_ptr< PandaFramework > framework, PointerTo< WindowFramework > window) VP_OVERRIDE
 
void initFromParent (const vpPanda3DBaseRenderer &renderer) VP_OVERRIDE
 
void setCameraPose (const vpHomogeneousMatrix &wTc) VP_OVERRIDE
 
vpHomogeneousMatrix getCameraPose () VP_OVERRIDE
 
void setNodePose (const std::string &name, const vpHomogeneousMatrix &wTo) VP_OVERRIDE
 
void setNodePose (NodePath &object, const vpHomogeneousMatrix &wTo) VP_OVERRIDE
 
vpHomogeneousMatrix getNodePose (const std::string &name) VP_OVERRIDE
 
vpHomogeneousMatrix getNodePose (NodePath &object) VP_OVERRIDE
 
void addNodeToScene (const NodePath &object) VP_OVERRIDE
 
virtual void setRenderParameters (const vpPanda3DRenderParameters &params) VP_OVERRIDE
 
void addLight (const vpPanda3DLight &light) VP_OVERRIDE
 
void addSubRenderer (std::shared_ptr< vpPanda3DBaseRenderer > renderer)
 
void enableSharedDepthBuffer (vpPanda3DBaseRenderer &sourceBuffer) VP_OVERRIDE
 
template<typename RendererType >
std::shared_ptr< RendererType > getRenderer ()
 
template<typename RendererType >
std::shared_ptr< RendererType > getRenderer (const std::string &name)
 
void beforeFrameRendered () VP_OVERRIDE
 
void afterFrameRendered () VP_OVERRIDE
 
virtual void renderFrame ()
 
const std::string & getName () const
 
void setName (const std::string &name)
 
NodePath & getRenderRoot ()
 
virtual bool isRendering3DScene () const
 
int getRenderOrder () const
 
void setRenderOrder (int order)
 
void computeNearAndFarPlanesFromNode (const std::string &name, float &near, float &far, bool fast)
 
NodePath loadObject (const std::string &nodeName, const std::string &modelPath)
 
void setVerticalSyncEnabled (bool useVsync)
 
void setAbortOnPandaError (bool abort)
 
void enableDebugLog ()
 
void printStructure ()
 
virtual GraphicsOutput * getMainOutputBuffer ()
 

Static Public Member Functions

static vpColVector vispPointToPanda (const vpColVector &point)
 
static vpColVector vispVectorToPanda (const vpColVector &vec)
 

Protected Member Functions

void setupScene () VP_OVERRIDE
 
void setupCamera () VP_OVERRIDE
 
virtual void setupRenderTarget ()
 

Protected Attributes

std::vector< std::shared_ptr< vpPanda3DBaseRenderer > > m_subRenderers
 
std::string m_name
 
int m_renderOrder
 
std::shared_ptr< PandaFramework > m_framework
 
PointerTo< WindowFramework > m_window
 
vpPanda3DRenderParameters m_renderParameters
 
NodePath m_renderRoot
 
PointerTo< Camera > m_camera
 
NodePath m_cameraPath
 
std::vector< GraphicsOutput * > m_buffers
 

Static Protected Attributes

static const vpHomogeneousMatrix VISP_T_PANDA
 
static const vpHomogeneousMatrix PANDA_T_VISP
 

Detailed Description

Class that rendering multiple datatypes, in a single pass. A RendererSet contains multiple subrenderers, all inheriting from vpPanda3DBaseRenderer. The renderer set synchronizes all scene properties for the different subrenderers. This includes:

  • The camera properties (intrinsics, resolution) and extrinsics
  • The pose and properties of every object in the scene
  • The pose and properties of lights, for subrenderers that are defined as lightable.

The overall usage workflow is the following:

  1. Create vpPanda3DRendererSet instance
  2. Create the subrenderers (e.g, vpPanda3DGeometryRenderer)
  3. Add the subrenderers to the set with addSubRenderer
  4. Call renderFrame() on the rendererSet. Each subrenderer now has its output computed and ready to be retrieved
  5. Retrieve relevant outputs in ViSP format with something similar to rendererSet.getRenderer<RendererType>("MyRendererName").getRender(I) where RendererType is the relevant subclass of vpPanda3DBaseRenderer and "MyRendererName" its name (see vpPanda3DBaseRenderer::getName)
Examples
tutorial-panda3d-renderer.cpp.

Definition at line 60 of file vpPanda3DRendererSet.h.

Constructor & Destructor Documentation

◆ vpPanda3DRendererSet()

BEGIN_VISP_NAMESPACE vpPanda3DRendererSet::vpPanda3DRendererSet ( const vpPanda3DRenderParameters renderParameters)

◆ ~vpPanda3DRendererSet()

virtual vpPanda3DRendererSet::~vpPanda3DRendererSet ( )
virtualdefault

Member Function Documentation

◆ addLight()

void vpPanda3DRendererSet::addLight ( const vpPanda3DLight light)
virtual

Light this lightable object with a new light.

Parameters
light

Implements vpPanda3DLightable.

Definition at line 155 of file vpPanda3DRendererSet.cpp.

References vpPanda3DLightable::addLight(), and m_subRenderers.

◆ addNodeToScene()

void vpPanda3DRendererSet::addNodeToScene ( const NodePath &  object)
virtual
Warning
This method is not supported and will throw

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 138 of file vpPanda3DRendererSet.cpp.

References m_subRenderers.

◆ addSubRenderer()

void vpPanda3DRendererSet::addSubRenderer ( std::shared_ptr< vpPanda3DBaseRenderer renderer)

Add a new subrenderer: This subrenderer should have a unique name, not present in the set.

Exceptions
ifthe subrenderer's name is already present in the set.
Parameters
rendererthe renderer to add

Definition at line 165 of file vpPanda3DRendererSet.cpp.

References vpException::badValue, getCameraPose(), vpPanda3DBaseRenderer::m_framework, vpPanda3DBaseRenderer::m_renderParameters, m_subRenderers, and vpPanda3DBaseRenderer::m_window.

◆ afterFrameRendered()

void vpPanda3DRendererSet::afterFrameRendered ( )
inlinevirtual

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 200 of file vpPanda3DRendererSet.h.

◆ beforeFrameRendered()

void vpPanda3DRendererSet::beforeFrameRendered ( )
inlinevirtual

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 193 of file vpPanda3DRendererSet.h.

◆ computeNearAndFarPlanesFromNode()

void vpPanda3DBaseRenderer::computeNearAndFarPlanesFromNode ( const std::string &  name,
float &  near,
float &  far,
bool  fast 
)
inherited

Compute the near and far planes for the camera at the current pose, given a certain node/part of the graph.

The near clipping value will be set to the distance to the closest point of the object. The far clipping value will be set to the distance to farthest vertex of the object.

Warning
Depending on geometry complexity, this may be an expensive operation.
if the object lies partly behind the camera, the near plane value will be zero. If it fully behind, the far plane will also be zero. If these near/far values are used to update the rendering parameters of the camera, this may result in an invalid projection matrix.
Parameters
namename of the node that should be used to compute near and far values.
nearresulting near clipping plane distance
farresulting far clipping plane distance
fastWhether to use the axis align bounding box to compute the clipping planes. This is faster than reprojecting the full geometry in the camera frame

Definition at line 191 of file vpPanda3DBaseRenderer.cpp.

References vpException::badValue, vpException::fatalError, vpPanda3DBaseRenderer::getCameraPose(), vpPanda3DBaseRenderer::getNodePose(), vpHomogeneousMatrix::inverse(), vpPanda3DBaseRenderer::m_camera, vpPanda3DBaseRenderer::m_cameraPath, vpPanda3DBaseRenderer::m_renderRoot, vpTime::measureTimeMs(), vpException::notInitialized, and vpPanda3DBaseRenderer::PANDA_T_VISP.

◆ enableDebugLog()

void vpPanda3DBaseRenderer::enableDebugLog ( )
inherited

Definition at line 313 of file vpPanda3DBaseRenderer.cpp.

◆ enableSharedDepthBuffer()

void vpPanda3DRendererSet::enableSharedDepthBuffer ( vpPanda3DBaseRenderer sourceBuffer)
virtual

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 188 of file vpPanda3DRendererSet.cpp.

References m_subRenderers.

◆ getCameraPose()

vpHomogeneousMatrix vpPanda3DRendererSet::getCameraPose ( )
virtual

Retrieve the pose of the camera. As this renderer contains multiple other renderers.

Warning
It is assumed that all the sub renderers are synchronized (i.e., the setCameraPose of this renderer was called before calling this method). Otherwise, you may get incoherent results.
Returns
the pose of the camera using the ViSP convention

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 97 of file vpPanda3DRendererSet.cpp.

References vpException::fatalError, vpPanda3DBaseRenderer::isRendering3DScene(), and m_subRenderers.

Referenced by addSubRenderer().

◆ getMainOutputBuffer()

virtual GraphicsOutput* vpPanda3DBaseRenderer::getMainOutputBuffer ( )
inlinevirtualinherited

◆ getName()

const std::string& vpPanda3DBaseRenderer::getName ( ) const
inlineinherited

Get the name of the renderer.

Returns
const std::string&

Definition at line 92 of file vpPanda3DBaseRenderer.h.

◆ getNodePose() [1/2]

vpHomogeneousMatrix vpPanda3DRendererSet::getNodePose ( const std::string &  name)
virtual

Retrieve the pose of a scene node. The pose is in the world frame, using a ViSP convention.

See also
the base method
Warning
It is assumed that all the sub renderers are synchronized (i.e., the setNodePose of this renderer was called before calling this method). Otherwise, you may get incoherent results.
Parameters
namename of the node
Returns
vpHomogeneousMatrix the pose of the node in the world frame

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 122 of file vpPanda3DRendererSet.cpp.

References vpException::fatalError, vpPanda3DBaseRenderer::isRendering3DScene(), and m_subRenderers.

◆ getNodePose() [2/2]

vpHomogeneousMatrix vpPanda3DRendererSet::getNodePose ( NodePath &  object)
virtual

This method is not supported for this renderer type. Use the std::string version.

Exceptions
vpException,asthis method is not supported
Parameters
object

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 133 of file vpPanda3DRendererSet.cpp.

References vpException::badValue.

◆ getRenderer() [1/2]

template<typename RendererType >
std::shared_ptr<RendererType> vpPanda3DRendererSet::getRenderer ( )
inline

Retrieve the first subrenderer with the specified template type.

Template Parameters
RendererTypeThe type of the renderer to find
Returns
std::shared_ptr<RendererType> Pointer to the first renderer match, nullptr if none is found.

Definition at line 161 of file vpPanda3DRendererSet.h.

◆ getRenderer() [2/2]

template<typename RendererType >
std::shared_ptr<RendererType> vpPanda3DRendererSet::getRenderer ( const std::string &  name)
inline

Retrieve the subrenderer with the specified template type and the given name.

Parameters
namethe name of the subrenderer to find
Template Parameters
RendererTypeThe type of the renderer to find
Returns
std::shared_ptr<RendererType> Pointer to the renderer, nullptr if none is found.

Definition at line 180 of file vpPanda3DRendererSet.h.

◆ getRenderOrder()

int vpPanda3DBaseRenderer::getRenderOrder ( ) const
inlineinherited

Get the rendering order of this renderer. If a renderer A has a lower order value than B, it will be rendered before B. This is useful, if for instance, B is a postprocessing filter that depends on the result of B.

Returns
int

Definition at line 123 of file vpPanda3DBaseRenderer.h.

Referenced by vpPanda3DPostProcessFilter::vpPanda3DPostProcessFilter().

◆ getRenderRoot()

NodePath& vpPanda3DBaseRenderer::getRenderRoot ( )
inlineinherited

Get the scene root.

Definition at line 100 of file vpPanda3DBaseRenderer.h.

◆ initFramework()

void vpPanda3DRendererSet::initFramework ( )
virtual

Initialize the framework and propagate the created panda3D framework to the subrenderers.

The subrenderers will be initialized in the order of their priority as defined by vpPanda3DBaseRenderer::getRenderOrder 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).

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 46 of file vpPanda3DRendererSet.cpp.

References vpException::fatalError, vpPanda3DRenderParameters::getImageHeight(), vpPanda3DRenderParameters::getImageWidth(), vpPanda3DBaseRenderer::m_framework, vpPanda3DBaseRenderer::m_renderParameters, m_subRenderers, vpPanda3DBaseRenderer::m_window, and vpException::notImplementedError.

◆ initFromParent() [1/2]

void vpPanda3DRendererSet::initFromParent ( const vpPanda3DBaseRenderer renderer)
virtual

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 80 of file vpPanda3DRendererSet.cpp.

References vpPanda3DBaseRenderer::initFromParent(), and m_subRenderers.

◆ initFromParent() [2/2]

void vpPanda3DRendererSet::initFromParent ( std::shared_ptr< PandaFramework >  framework,
PointerTo< WindowFramework >  window 
)
virtual

◆ isRendering3DScene()

virtual bool vpPanda3DBaseRenderer::isRendering3DScene ( ) const
inlinevirtualinherited

Returns true if this renderer process 3D data and its scene root can be interacted with.

This value could be false, if for instance it is redefined in a subclass that performs postprocessing on a texture.

Reimplemented in vpPanda3DPostProcessFilter.

Definition at line 114 of file vpPanda3DBaseRenderer.h.

Referenced by vpPanda3DBaseRenderer::enableSharedDepthBuffer(), getCameraPose(), and getNodePose().

◆ loadObject()

NodePath vpPanda3DBaseRenderer::loadObject ( const std::string &  nodeName,
const std::string &  modelPath 
)
inherited

Load a 3D object. To load an .obj file, Panda3D must be compiled with assimp support.

Once loaded, the object will not be visible, it should be added to the scene.

Parameters
nodeNamethe name that will be used when inserting the node in the scene graph
modelPathPath to the model file
Returns
NodePath The NodePath containing the 3D model, which can now be added to the scene graph.

Definition at line 275 of file vpPanda3DBaseRenderer.cpp.

References vpPanda3DBaseRenderer::m_framework, and vpPanda3DBaseRenderer::m_window.

◆ printStructure()

void vpPanda3DBaseRenderer::printStructure ( )
inherited

Definition at line 331 of file vpPanda3DBaseRenderer.cpp.

References vpPanda3DBaseRenderer::m_renderRoot.

◆ renderFrame()

void vpPanda3DBaseRenderer::renderFrame ( )
virtualinherited

◆ setAbortOnPandaError()

void vpPanda3DBaseRenderer::setAbortOnPandaError ( bool  abort)
inherited

Set the behaviour when a Panda3D assertion fails. If abort is true, the program will stop. Otherwise, an error will be displayed in the console.

Parameters
abortwhether to abort (true) or display a message when an assertion fails.

Definition at line 303 of file vpPanda3DBaseRenderer.cpp.

◆ setCameraPose()

void vpPanda3DRendererSet::setCameraPose ( const vpHomogeneousMatrix wTc)
virtual

Set the pose of the camera, using the ViSP convention. This change is propagated to all subrenderers.

Parameters
wTcPose of the camera

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 88 of file vpPanda3DRendererSet.cpp.

References m_subRenderers.

◆ setName()

void vpPanda3DBaseRenderer::setName ( const std::string &  name)
inlineinherited

Definition at line 94 of file vpPanda3DBaseRenderer.h.

◆ setNodePose() [1/2]

void vpPanda3DRendererSet::setNodePose ( const std::string &  name,
const vpHomogeneousMatrix wTo 
)
virtual

Set the pose of an object for all the subrenderers. The pose is specified using the ViSP convention This method may fail if a subrenderer does not have a node with the given name.

Warning
This method may fail if a subrenderer does not have a node with the given name. It is assumed that the scenes are synchronized
Parameters
name
wTo

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 108 of file vpPanda3DRendererSet.cpp.

References m_subRenderers.

◆ setNodePose() [2/2]

void vpPanda3DRendererSet::setNodePose ( NodePath &  object,
const vpHomogeneousMatrix wTo 
)
virtual

This method is not supported for this renderer type. Use the std::string version.

Exceptions
vpException,asthis method is not supported
Parameters
object
wTo

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 117 of file vpPanda3DRendererSet.cpp.

References vpException::badValue.

◆ setRenderOrder()

void vpPanda3DBaseRenderer::setRenderOrder ( int  order)
inlineinherited

Definition at line 125 of file vpPanda3DBaseRenderer.h.

◆ setRenderParameters()

void vpPanda3DRendererSet::setRenderParameters ( const vpPanda3DRenderParameters params)
virtual

Set new rendering parameters. If the scene has already been initialized, the renderer camera is updated.

Parameters
paramsthe new rendering parameters

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 147 of file vpPanda3DRendererSet.cpp.

References vpPanda3DBaseRenderer::m_renderParameters, and m_subRenderers.

◆ setupCamera()

void vpPanda3DRendererSet::setupCamera ( )
inlineprotectedvirtual

Initialize camera. Should be called when the scene root of this render has already been created.

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 210 of file vpPanda3DRendererSet.h.

◆ setupRenderTarget()

virtual void vpPanda3DBaseRenderer::setupRenderTarget ( )
inlineprotectedvirtualinherited

Initialize buffers and other objects that are required to save the render.

Reimplemented in vpPanda3DRGBRenderer, vpPanda3DPostProcessFilter, and vpPanda3DGeometryRenderer.

Definition at line 265 of file vpPanda3DBaseRenderer.h.

Referenced by vpPanda3DBaseRenderer::initFramework(), and vpPanda3DBaseRenderer::initFromParent().

◆ setupScene()

void vpPanda3DRendererSet::setupScene ( )
inlineprotectedvirtual

Initialize the scene for this specific renderer.

Creates a root scene for this node and applies shaders. that will be used for rendering

Reimplemented from vpPanda3DBaseRenderer.

Definition at line 208 of file vpPanda3DRendererSet.h.

◆ setVerticalSyncEnabled()

void vpPanda3DBaseRenderer::setVerticalSyncEnabled ( bool  useVsync)
inherited

set whether vertical sync is enabled. When vertical sync is enabled, render speed will be limited by the display's refresh rate

Parameters
useVsyncWhether to use vsync or not

Definition at line 294 of file vpPanda3DBaseRenderer.cpp.

◆ vispPointToPanda()

vpColVector vpPanda3DBaseRenderer::vispPointToPanda ( const vpColVector point)
staticinherited

Definition at line 319 of file vpPanda3DBaseRenderer.cpp.

References vpPanda3DBaseRenderer::PANDA_T_VISP.

◆ vispVectorToPanda()

vpColVector vpPanda3DBaseRenderer::vispVectorToPanda ( const vpColVector vec)
staticinherited

Member Data Documentation

◆ m_buffers

◆ m_camera

PointerTo<Camera> vpPanda3DBaseRenderer::m_camera
protectedinherited

◆ m_cameraPath

◆ m_framework

std::shared_ptr<PandaFramework> vpPanda3DBaseRenderer::m_framework
protectedinherited

Rendering priority for this renderer and its buffers. A lower value will be rendered first. Should be used when calling make_output in setupRenderTarget()

Definition at line 273 of file vpPanda3DBaseRenderer.h.

Referenced by addSubRenderer(), vpPanda3DBaseRenderer::initFramework(), initFramework(), vpPanda3DBaseRenderer::initFromParent(), initFromParent(), vpPanda3DBaseRenderer::loadObject(), and vpPanda3DBaseRenderer::renderFrame().

◆ m_name

std::string vpPanda3DBaseRenderer::m_name
protectedinherited

◆ m_renderOrder

int vpPanda3DBaseRenderer::m_renderOrder
protectedinherited

◆ m_renderParameters

◆ m_renderRoot

◆ m_subRenderers

std::vector<std::shared_ptr<vpPanda3DBaseRenderer> > vpPanda3DRendererSet::m_subRenderers
protected

◆ m_window

◆ PANDA_T_VISP

const vpHomogeneousMatrix vpPanda3DBaseRenderer::PANDA_T_VISP
staticprotectedinherited

Homogeneous transformation matrix to convert from the Panda coordinate system (right-handed Z-up) to the ViSP coordinate system (right-handed Y-Down)

Definition at line 268 of file vpPanda3DBaseRenderer.h.

Referenced by vpPanda3DBaseRenderer::computeNearAndFarPlanesFromNode(), vpPanda3DBaseRenderer::getNodePose(), vpPanda3DBaseRenderer::vispPointToPanda(), and vpPanda3DBaseRenderer::vispVectorToPanda().

◆ VISP_T_PANDA

BEGIN_VISP_NAMESPACE const vpHomogeneousMatrix vpPanda3DBaseRenderer::VISP_T_PANDA
staticprotectedinherited

Definition at line 267 of file vpPanda3DBaseRenderer.h.

Referenced by vpPanda3DBaseRenderer::setNodePose().