class mrpt::viz::CVisualObject

Overview

The base class of 3D objects that can be directly rendered through OpenGL.

In this class there are a set of common properties to all 3D objects, mainly:

  • Its SE(3) pose (x,y,z,yaw,pitch,roll), relative to the parent object, or the global frame of reference for root objects (inserted into a mrpt::viz::Scene).

  • A name: A name that can be optionally assigned to objects for easing its reference.

  • A RGBA color: This field will be used in simple elements (points, lines, text,…) but is ignored in more complex objects that carry their own color information (triangle sets,…)

  • Shininess: See materialShininess(float)

See the main class opengl::Scene

RENDERING FLOW

  1. User modifies a viz object (e.g., box.setBoxCorners(…)) → This calls notifyChange() which sets the dirty flag

  2. CompiledScene::updateIfNeeded() is called before rendering → For each tracked object with hasToUpdateBuffers() == true: a) Call sourceObj-> updateBuffers() ← populates viz buffers b) Call proxy->updateBuffers(sourceObj) ← Uploads to GPU

  3. Rendering proceeds with the updated GPU buffers

See also:

opengl::Scene, mrpt::viz

#include <mrpt/viz/CVisualObject.h>

class CVisualObject: public mrpt::serialization::CSerializable
{
public:
    // structs

    struct PoseAndScale;
    struct State;

    // methods

    virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const;
};

// direct descendants

template <int DIM>
class CGeneralizedEllipsoidTemplate;

class CArrow;
class CAxis;
class CBox;
class CCamera;
class CColorBar;
class CCylinder;
class CDisk;
class CEllipsoidInverseDepth3D;
class CEllipsoidRangeBearing2D;
class CFrustum;
class CGridPlaneXY;
class CGridPlaneXZ;
class CMesh;
class CMesh3D;
class CMeshFast;
class COctoMapVoxels;
class CPlanarLaserScan;
class CPointCloud;
class CPointCloudColoured;
class CPolyhedron;
class CSetOfLines;
class CSetOfObjects;
class CSetOfTexturedTriangles;
class CSetOfTriangles;
class CSimpleLine;
class CSkyBox;
class CText;
class CText3D;
class CTexturedPlane;
class CVectorField2D;
class CVectorField3D;
class VisualObjectParams_Lines;
class VisualObjectParams_Points;
class VisualObjectParams_TexturedTriangles;
class VisualObjectParams_Triangles;

Inherited Members

public:
    // typedefs

    typedef std::shared_ptr<CObject> Ptr;
    typedef std::shared_ptr<const CObject> ConstPtr;
    typedef std::shared_ptr<CSerializable> Ptr;
    typedef std::shared_ptr<const CSerializable> ConstPtr;

    // methods

    static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic();
    virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const;
    virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const;
    static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic();

Methods

virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const

Returns information about the class of an object in runtime.