class mrpt::opengl::COctoMapVoxels
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::opengl::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::opengl class, all object coordinates refer to some frame of reference which is relative to the object parent and can be changed with mrpt::opengl::CRenderizable::setPose()
This class draws these separate elements to represent an OctoMap:
A grid representation of all cubes, as simple lines (occupied/free, leafs/nodes,… whatever). See:
A number of voxel collections, drawn as cubes each having a different color (e.g. depending on the color scheme in the original mrpt::maps::COctoMap object). The meanning of each collection is user-defined, but you can use the constants VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE for predefined meanings.
Several coloring schemes can be selected with setVisualizationMode(). See COctoMapVoxels::visualization_mode_t
See also:
#include <mrpt/opengl/COctoMapVoxels.h> class COctoMapVoxels: public mrpt::opengl::CRenderizableShaderTriangles, public mrpt::opengl::CRenderizableShaderWireFrame, public mrpt::opengl::CRenderizableShaderPoints { public: // enums enum visualization_mode_t; // structs struct TGridCube; struct TInfoPerVoxelSet; struct TVoxel; // construction COctoMapVoxels(); // methods virtual void render(const RenderContext& rc) const; virtual void renderUpdateBuffers() const; virtual shader_list_t requiredShaders() const; virtual void onUpdateBuffers_Points(); virtual void onUpdateBuffers_Wireframe(); virtual void onUpdateBuffers_Triangles(); virtual void freeOpenGLResources(); 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(const size_t set_index) const; void setBoundingBox(const mrpt::math::TPoint3D& bb_min, const mrpt::math::TPoint3D& bb_max); void resizeGridCubes(const size_t nCubes); void resizeVoxelSets(const size_t nVoxelSets); void resizeVoxels( const size_t set_index, const size_t nVoxels ); void reserveGridCubes(const size_t nCubes); void reserveVoxels( const size_t set_index, const size_t nVoxels ); TGridCube& getGridCubeRef(const size_t idx); const TGridCube& getGridCube(const size_t idx) const; TVoxel& getVoxelRef( const size_t set_index, const size_t idx ); const TVoxel& getVoxel( const size_t set_index, const size_t idx ) const; void push_back_GridCube(const TGridCube& c); void push_back_Voxel( const size_t set_index, const TVoxel& v ); void sort_voxels_by_z(); virtual mrpt::math::TBoundingBox getBoundingBox() const; template <class OCTOMAP> void setFromOctoMap(OCTOMAP& m); };
Inherited Members
public: // structs struct RenderContext; // methods virtual void render(const RenderContext& rc) const = 0; virtual void renderUpdateBuffers() const = 0; virtual shader_list_t requiredShaders() const; virtual auto getBoundingBox() const = 0; virtual void freeOpenGLResources() = 0; virtual void onUpdateBuffers_Triangles() = 0; virtual void onUpdateBuffers_Wireframe() = 0; virtual void onUpdateBuffers_Points() = 0;
Construction
COctoMapVoxels()
Constructor.
Ctor.
Methods
virtual void render(const RenderContext& rc) const
Implements the rendering of 3D objects in each class derived from CRenderizable.
This can be called more than once (one per required shader program) if the object registered several shaders.
See also:
virtual void renderUpdateBuffers() const
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
before they are sent for rendering in render()
virtual shader_list_t requiredShaders() const
Returns the ID of the OpenGL shader program required to render this class.
See also:
virtual void onUpdateBuffers_Points()
Must be implemented in derived classes to update the geometric entities to be drawn in “m_*_buffer” fields.
virtual void onUpdateBuffers_Wireframe()
Must be implemented in derived classes to update the geometric entities to be drawn in “m_*_buffer” fields.
virtual void onUpdateBuffers_Triangles()
Must be implemented in derived classes to update the geometric entities to be drawn in “m_*_buffer” fields.
virtual void freeOpenGLResources()
Free opengl buffers.
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:
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(const 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::TBoundingBox getBoundingBox() const
Evaluates the bounding box of this object (including possible children) in the coordinate frame of the object parent.
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 |