Class CVisualObject

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public mrpt::serialization::CSerializable

Derived Types

Class Documentation

class CVisualObject : public mrpt::serialization::CSerializable

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

Subclassed by mrpt::viz::CGeneralizedEllipsoidTemplate< 2 >, mrpt::viz::CGeneralizedEllipsoidTemplate< 3 >, mrpt::viz::CAngularObservationMesh, mrpt::viz::CArrow, mrpt::viz::CAxis, mrpt::viz::CBox, mrpt::viz::CCamera, mrpt::viz::CColorBar, mrpt::viz::CCylinder, mrpt::viz::CDisk, mrpt::viz::CEllipsoidInverseDepth3D, mrpt::viz::CEllipsoidRangeBearing2D, mrpt::viz::CFrustum, mrpt::viz::CGeneralizedEllipsoidTemplate< DIM >, mrpt::viz::CGridPlaneXY, mrpt::viz::CGridPlaneXZ, mrpt::viz::CMesh, mrpt::viz::CMesh3D, mrpt::viz::CMeshFast, mrpt::viz::COctoMapVoxels, mrpt::viz::CPlanarLaserScan, mrpt::viz::CPointCloud, mrpt::viz::CPointCloudColoured, mrpt::viz::CPolyhedron, mrpt::viz::CSetOfLines, mrpt::viz::CSetOfObjects, mrpt::viz::CSetOfTexturedTriangles, mrpt::viz::CSetOfTriangles, mrpt::viz::CSimpleLine, mrpt::viz::CSkyBox, mrpt::viz::CText, mrpt::viz::CText3D, mrpt::viz::CTexturedPlane, mrpt::viz::CVectorField2D, mrpt::viz::CVectorField3D, mrpt::viz::VisualObjectParams_Lines, mrpt::viz::VisualObjectParams_Points, mrpt::viz::VisualObjectParams_TexturedTriangles, mrpt::viz::VisualObjectParams_Triangles

Changes the appearance of the object to render

inline void setName(const std::string &n)

Changes the name of the object

inline std::string getName() const

Returns the name of the object

inline bool isVisible() const

Is the object visible?

See also

setVisibility

inline void setVisibility(bool visible = true)

Set object visibility (default=true)

See also

isVisible

inline bool castShadows() const

Does the object cast shadows? (default=true)

inline void castShadows(bool doCast = true)

Enable/disable casting shadows by this object (default=true)

inline void enableShowName(bool showName = true)

Enables or disables showing the name of the object as a label when rendering

inline bool isShowNameEnabled() const

See also

enableShowName

CVisualObject &setPose(const mrpt::poses::CPose3D &o)

Defines the SE(3) (pose=translation+rotation) of the object with respect to its parent

CVisualObject &setPose(const mrpt::poses::CPose2D &o)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

CVisualObject &setPose(const mrpt::math::TPose3D &o)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

CVisualObject &setPose(const mrpt::math::TPose2D &o)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

CVisualObject &setPose(const mrpt::poses::CPoint3D &o)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

CVisualObject &setPose(const mrpt::poses::CPoint2D &o)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

mrpt::math::TPose3D getPose() const

Returns the 3D pose of the object as TPose3D

inline PoseAndScale getPoseAndScale() const
inline mrpt::poses::CPose3D getCPose() const

Returns a const ref to the 3D pose of the object as mrpt::poses::CPose3D (which explicitly contains the 3x3 rotation matrix)

inline CVisualObject &setLocation(double x, double y, double z)

Changes the location of the object, keeping untouched the orientation

Returns:

a ref to this

inline CVisualObject &setLocation(const mrpt::math::TPoint3D &p)

Changes the location of the object, keeping untouched the orientation

Returns:

a ref to this

inline mrpt::img::TColorf getColor() const

Get color components as floats in the range [0,1]

inline mrpt::img::TColor getColor_u8() const

Get color components as uint8_t in the range [0,255]

inline CVisualObject &setColorA(const float a)

Set alpha (transparency) color component in the range [0,1]

Returns:

a ref to this

inline virtual CVisualObject &setColorA_u8(const uint8_t a)

Set alpha (transparency) color component in the range [0,255]

Returns:

a ref to this

inline float materialShininess() const

Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)

inline void materialShininess(float shininess)

Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)

inline float materialSpecularExponent() const

Blinn-Phong specular exponent. Higher values produce a smaller, sharper specular highlight. Typical values: 8 (rough), 32 (default), 128 (metal).

inline void materialSpecularExponent(float exponent)

Blinn-Phong specular exponent. Higher values produce a smaller, sharper specular highlight. Typical values: 8 (rough), 32 (default), 128 (metal).

inline mrpt::img::TColorf materialEmissive() const

Emissive color: light emitted by the object regardless of scene lighting. Default is black (no emission). Useful for displays, indicator lights, laser beams, warning signs, etc. The emissive term is added to the final lighting equation as: finalColor = emissive + (ambient + diffuse + specular) * materialColor

inline void materialEmissive(const mrpt::img::TColorf &color)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline CVisualObject &setScale(float s)

Scale to apply to the object, in all three axes (default=1)

Returns:

a ref to this

inline CVisualObject &setScale(float sx, float sy, float sz)

Scale to apply to the object in each axis (default=1)

Returns:

a ref to this

inline float getScaleX() const

Get the current scaling factor in one axis

inline float getScaleY() const

Get the current scaling factor in one axis

inline float getScaleZ() const

Get the current scaling factor in one axis

inline CVisualObject &setColor(const mrpt::img::TColorf &c)

Changes the default object color

Returns:

a ref to this

inline CVisualObject &setColor(float R, float G, float B, float A = 1)

Set the color components of this object (R,G,B,Alpha, in the range 0-1)

Returns:

a ref to this

virtual CVisualObject &setColor_u8(const mrpt::img::TColor &c)
inline CVisualObject &setColor_u8(uint8_t R, uint8_t G, uint8_t B, uint8_t A = 255)

Set the color components of this object (R,G,B,Alpha, in the range 0-255)

Returns:

a ref to this

Public Functions

inline virtual bool cullElegible() const

Return false if this object should never be checked for being culled out (=not rendered if its bbox are out of the screen limits). For example, skyboxes or other special effects.

virtual void toYAMLMap(mrpt::containers::yaml &propertiesMap) const

Used from Scene::asYAML().

Note

(New in MRPT 2.4.2)

inline virtual bool isCompositeObject() const

Should return true if enqueueForRenderRecursive() is defined since the object has inner children. Examples: CSetOfObjects, CAssimpModel.

inline virtual const std::deque<std::shared_ptr<CVisualObject>> &getInternalChildren() const

Returns internal children for composite objects (e.g. CAxis text labels). Only meaningful if isCompositeObject() returns true.

Note

Not for CSetOfObjects — those are handled as containers.

inline void notifyChange() const

Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.

inline void clearChangedFlag() const

Reset the dirty flag set with notifyChange().

Deprecated:

Prefer using the version-counter API: dataVersion() / hasToUpdateBuffersSince(). Kept for backwards compatibility; now a no-op.

inline void notifyBBoxChange() const
inline bool hasToUpdateBuffers() const

Returns whether notifyChange() has been invoked since the last call to renderUpdateBuffers(), meaning the latter needs to be called again before rendering.

Note

Prefer hasToUpdateBuffersSince() for multi-consumer scenarios.

inline uint64_t dataVersion() const

Returns the current data version counter. Incremented on each notifyChange() call. Use this with hasToUpdateBuffersSince() for multi-consumer dirty tracking.

inline bool hasToUpdateBuffersSince(uint64_t sinceVersion) const

Returns true if this object’s data has changed since the given version. Each consumer (e.g., CompiledScene) should store the last version it processed and pass it here.

inline virtual void updateBuffers() const

Called by the rendering system to update internal geometry buffers.

Derived classes should override this to populate their data buffers (triangles, points, lines) when the object geometry changes.

This is called automatically when hasToUpdateBuffers() returns true, which happens after notifyChange() was called.

The base implementation does nothing; derived classes should override.

Note

Thread safety: implementations should lock the appropriate mutexes when writing to shared buffers.

virtual bool traceRay(const mrpt::poses::CPose3D &o, double &dist) const

Simulation of ray-trace, given a pose. Returns true if the ray effectively collisions with the object (returning the distance to the origin of the ray in “dist”), or false in other case. “dist” variable yields undefined behaviour when false is returned

inline auto getBoundingBox() const -> mrpt::math::TBoundingBox

Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e. if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()

auto getBoundingBoxLocal() const -> mrpt::math::TBoundingBox

Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e. if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()

auto getBoundingBoxLocalf() const -> mrpt::math::TBoundingBoxf
inline virtual mrpt::math::TPoint3Df getLocalRepresentativePoint() const

Provide a representative point (in object local coordinates), used to sort objects by eye-distance while rendering with transparencies (Default=[0,0,0])

inline void setLocalRepresentativePoint(const mrpt::math::TPoint3Df &p)

See getLocalRepresentativePoint()

mrpt::viz::CText &labelObject() const

Returns or constructs (in its first invocation) the associated mrpt::viz::CText object representing the label of the object.

See also

enableShowName()

std::shared_ptr<mrpt::viz::CText> labelObjectPtr() const

Returns the shared_ptr to the label object (creating it if needed).

Protected Functions

void writeToStreamRender(mrpt::serialization::CArchive &out) const
void readFromStreamRender(mrpt::serialization::CArchive &in)
virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const = 0

Must be implemented by derived classes to provide the updated bounding box in the object local frame of coordinates. This will be called only once after each time the derived class reports to notifyChange() that the object geometry changed.

See also

getBoundingBox(), getBoundingBoxLocal(), getBoundingBoxLocalf()

Protected Attributes

State m_state

All relevant rendering state that needs to get protected by m_stateMtx.

mutable mrpt::containers::NonCopiableData<std::shared_mutex> m_stateMtx
mutable uint64_t m_dataVersion = {1}
mutable mrpt::containers::NonCopiableData<std::shared_mutex> m_outdatedStateMtx
mutable std::optional<mrpt::math::TBoundingBoxf> m_cachedLocalBBox
mutable std::shared_ptr<mrpt::viz::CText> m_label_obj

Optional pointer to a mrpt::viz::CText

Friends

friend class mrpt::viz::Viewport
friend class mrpt::viz::CSetOfObjects
struct PoseAndScale

Atomically reads pose, scale, and visibility under a single lock. Use this when you need a consistent snapshot of the object’s transform.

Public Members

mrpt::poses::CPose3D pose
float scaleX = 1
float scaleY = 1
float scaleZ = 1
bool visible = true
struct State

Public Members

std::string name
bool show_name = false
mrpt::img::TColor color = {0xff, 0xff, 0xff, 0xff}

RGBA components in the range [0,255]

float materialShininess = 0.2f
float materialSpecularExponent = 16.0f

Specular exponent for Blinn-Phong lighting (higher = sharper highlight). Typical values: 8 (rough), 32 (default, plastic), 128 (metal/mirror).

mrpt::img::TColorf materialEmissive = {0, 0, 0, 0}

Emissive color: light emitted by the object regardless of scene lighting. Default is black (no emission). Useful for displays, indicator lights, laser beams, etc.

mrpt::poses::CPose3D pose

SE(3) pose wrt the parent coordinate reference. This class automatically holds the cached 3x3 rotation matrix for quick load into opengl stack.

float scale_x = 1.0f

Scale components to apply to the object (default=1)

float scale_y = 1.0f
float scale_z = 1.0f
bool visible = true

Is the object visible? (default=true)

bool castShadows = true
mrpt::math::TPoint3Df representativePoint = {0, 0, 0}