class mrpt::viz::COctoMapVoxels

Overview

A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).

This class is sort of equivalent to octovis::OcTreeDrawer from the octomap package, but relying on MRPT’s CRenderizable so there’s no need to manually cache the rendering of OpenGL primitives.

Normally users call mrpt::maps::COctoMap::getAs3DObject() to obtain a generic mrpt::viz::CSetOfObjects which insides holds an instance of COctoMapVoxels. You can also alternativelly call COctoMapVoxels::setFromOctoMap(), so you can tune the display parameters, colors, etc. As with any other mrpt::viz class, all object coordinates refer to some frame of reference which is relative to the object parent and can be changed with mrpt::viz::CVisualObject::setPose()

This class draws these separate elements to represent an OctoMap:

Several coloring schemes can be selected with setVisualizationMode(). See COctoMapVoxels::visualization_mode_t

mrpt::viz::COctoMapVoxels mrpt::viz::COctoMapVoxels mrpt::viz::COctoMapVoxels mrpt::viz::COctoMapVoxels

See also:

opengl::Scene

#include <mrpt/viz/COctoMapVoxels.h>

class COctoMapVoxels:
    public mrpt::viz::CVisualObject,
    public mrpt::viz::VisualObjectParams_Lines,
    public mrpt::viz::VisualObjectParams_Triangles,
    public mrpt::viz::VisualObjectParams_Points
{
public:
    // enums

    enum visualization_mode_t;

    // structs

    struct TGridCube;
    struct TInfoPerVoxelSet;
    struct TVoxel;

    // construction

    COctoMapVoxels();

    // methods

    mrpt::img::TColormap colorMap() const;
    void colorMap(const mrpt::img::TColormap& cm);
    void clear();
    void setVisualizationMode(visualization_mode_t mode);
    visualization_mode_t getVisualizationMode() const;
    void enableLights(bool enable);
    bool areLightsEnabled() const;
    void enableCubeTransparency(bool enable);
    bool isCubeTransparencyEnabled() const;
    void showGridLines(bool show);
    bool areGridLinesVisible() const;
    void showVoxels(unsigned int voxel_set, bool show);
    bool areVoxelsVisible(unsigned int voxel_set) const;
    void showVoxelsAsPoints(const bool enable);
    bool areVoxelsShownAsPoints() const;
    void setVoxelAsPointsSize(float pointSize);
    float getVoxelAsPointsSize() const;
    void setGridLinesWidth(float w);
    float getGridLinesWidth() const;
    void setGridLinesColor(const mrpt::img::TColor& color);
    const mrpt::img::TColor& getGridLinesColor() const;
    size_t getGridCubeCount() const;
    size_t getVoxelSetCount() const;
    size_t getVoxelCount(size_t set_index) const;
    void setBoundingBox(const mrpt::math::TPoint3D& bb_min, const mrpt::math::TPoint3D& bb_max);
    void resizeGridCubes(size_t nCubes);
    void resizeVoxelSets(size_t nVoxelSets);

    void resizeVoxels(
        size_t set_index,
        size_t nVoxels
        );

    void reserveGridCubes(size_t nCubes);

    void reserveVoxels(
        size_t set_index,
        size_t nVoxels
        );

    TGridCube& getGridCubeRef(size_t idx);
    const TGridCube& getGridCube(size_t idx) const;

    TVoxel& getVoxelRef(
        size_t set_index,
        size_t idx
        );

    const TVoxel& getVoxel(
        size_t set_index,
        size_t idx
        ) const;

    void push_back_GridCube(const TGridCube& c);

    void push_back_Voxel(
        size_t set_index,
        const TVoxel& v
        );

    void sort_voxels_by_z();
    virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const;

    template <class OCTOMAP>
    void setFromOctoMap(OCTOMAP& m);
};

Inherited Members

public:
    // typedefs

    typedef std::shared_ptr<CObject> Ptr;
    typedef std::shared_ptr<const CObject> ConstPtr;
    typedef std::unique_ptr<CObject> UniquePtr;
    typedef std::unique_ptr<const CObject> ConstUniquePtr;

    // structs

    struct OutdatedState;
    struct State;

    // methods

    void setLineWidth(float w);
    float getLineWidth() const;
    void enableAntiAliasing(bool enable = true);
    bool isAntiAliasingEnabled() const;
    const auto& shaderTrianglesBuffer() const;
    auto& shaderTrianglesBufferMutex() const;
    virtual CVisualObject& setColor_u8(const mrpt::img::TColor& c);
    bool isLightEnabled() const;
    void enableLight(bool enable = true);
    TCullFace cullFaces() const;
    void notifyBBoxChange() const;
    auto getBoundingBoxLocalf() const;
    static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic();
    const auto& shaderPointsVertexPointBuffer() const;
    const auto& shaderPointsVertexColorBuffer() const;
    auto& shaderPointsBuffersMutex() const;
    float getPointSize() const;
    bool isEnabledVariablePointSize() const;
    float getVariablePointSize_k() const;
    float getVariablePointSize_DepthScale() const;

Construction

COctoMapVoxels()

Constructor.

Ctor.

Methods

void colorMap(const mrpt::img::TColormap& cm)

Changing the colormap has no effect until a source object (e.g.

mrpt::maps::CVoxelMap) reads this property while generating the voxels visualization.

void clear()

Clears everything.

void setVisualizationMode(visualization_mode_t mode)

Select the visualization mode.

To have any effect, this method has to be called before loading the octomap.

void enableLights(bool enable)

Can be used to enable/disable the effects of lighting in this object.

void enableCubeTransparency(bool enable)

By default, the alpha (transparency) component of voxel cubes is taken into account, but transparency can be disabled with this method.

void showGridLines(bool show)

Shows/hides the grid lines.

void showVoxels(unsigned int voxel_set, bool show)

Shows/hides the voxels (voxel_set is a 0-based index for the set of voxels to modify, e.g.

VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE)

void showVoxelsAsPoints(const bool enable)

For quick renders: render voxels as points instead of cubes.

See also:

setVoxelAsPointsSize

void setVoxelAsPointsSize(float pointSize)

Only used when showVoxelsAsPoints() is enabled.

void setGridLinesWidth(float w)

Sets the width of grid lines.

float getGridLinesWidth() const

Gets the width of grid lines.

size_t getGridCubeCount() const

Returns the total count of grid cubes.

size_t getVoxelSetCount() const

Returns the number of voxel sets.

size_t getVoxelCount(size_t set_index) const

Returns the total count of voxels in one voxel set.

void setBoundingBox(const mrpt::math::TPoint3D& bb_min, const mrpt::math::TPoint3D& bb_max)

Manually changes the bounding box (normally the user doesn’t need to call this)

virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const

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()

template <class OCTOMAP>
void setFromOctoMap(OCTOMAP& m)

Sets the contents of the object from a mrpt::maps::COctoMap object.

Declared as a template because in the library [mrpt-opengl] we don’t have access to the library [mrpt-maps].

Parameters:

Typically

an

mrpt::maps::COctoMap object