Class COctoMapVoxels
Defined in File COctoMapVoxels.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Types
public mrpt::viz::CVisualObject(Class CVisualObject)public mrpt::viz::VisualObjectParams_Lines(Class VisualObjectParams_Lines)public mrpt::viz::VisualObjectParams_Triangles(Class VisualObjectParams_Triangles)public mrpt::viz::VisualObjectParams_Points(Class VisualObjectParams_Points)
Class Documentation
-
class COctoMapVoxels : public virtual mrpt::viz::CVisualObject, public mrpt::viz::VisualObjectParams_Lines, public mrpt::viz::VisualObjectParams_Triangles, public mrpt::viz::VisualObjectParams_Points
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:
A grid representation of all cubes, as simple lines (occupied/free, leafs/nodes,… whatever). See:
setGridLinesColor()
push_back_GridCube()
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.
push_back_Voxel()
Several coloring schemes can be selected with setVisualizationMode(). See COctoMapVoxels::visualization_mode_t

See also
opengl::Scene
Public Types
-
enum visualization_mode_t
The different coloring schemes, which modulate the generic mrpt::viz::CRenderizable object color. Set with setVisualizationMode()
Values:
-
enumerator COLOR_FROM_HEIGHT
Color goes from black (at the bottom) to the chosen color (at the top)
-
enumerator COLOR_FROM_OCCUPANCY
Color goes from black (occupied voxel) to the chosen color (free voxel)
-
enumerator TRANSPARENCY_FROM_OCCUPANCY
Transparency goes from opaque (occupied voxel) to transparent (free voxel).
-
enumerator TRANS_AND_COLOR_FROM_OCCUPANCY
Color goes from black (occupaid voxel) to the chosen color (free voxel) and they are transparent
-
enumerator MIXED
Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY
-
enumerator FIXED
All cubes are of identical color.
-
enumerator COLOR_FROM_RGB_DATA
Color from RGB data
-
enumerator COLOR_FROM_HEIGHT
Public Functions
-
inline mrpt::img::TColormap colorMap() const
-
inline 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
-
inline void setVisualizationMode(visualization_mode_t mode)
Select the visualization mode. To have any effect, this method has to be called before loading the octomap.
-
inline visualization_mode_t getVisualizationMode() const
-
inline void enableLights(bool enable)
Can be used to enable/disable the effects of lighting in this object
-
inline bool areLightsEnabled() const
-
inline 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.
-
inline bool isCubeTransparencyEnabled() const
-
inline void showGridLines(bool show)
Shows/hides the grid lines
-
inline bool areGridLinesVisible() const
-
inline 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)
-
inline bool areVoxelsVisible(unsigned int voxel_set) const
-
inline void showVoxelsAsPoints(const bool enable)
For quick renders: render voxels as points instead of cubes.
See also
-
inline bool areVoxelsShownAsPoints() const
-
inline void setVoxelAsPointsSize(float pointSize)
Only used when showVoxelsAsPoints() is enabled.
-
inline float getVoxelAsPointsSize() const
-
inline void setGridLinesWidth(float w)
Sets the width of grid lines
-
inline float getGridLinesWidth() const
Gets the width of grid lines
-
inline void setGridLinesColor(const mrpt::img::TColor &color)
-
inline const mrpt::img::TColor &getGridLinesColor() const
-
inline size_t getGridCubeCount() const
Returns the total count of grid cubes.
-
inline size_t getVoxelSetCount() const
Returns the number of voxel sets.
-
inline 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)
-
inline void resizeGridCubes(size_t nCubes)
-
inline void resizeVoxelSets(size_t nVoxelSets)
-
inline void resizeVoxels(size_t set_index, size_t nVoxels)
-
inline void reserveGridCubes(size_t nCubes)
-
inline void reserveVoxels(size_t set_index, size_t nVoxels)
-
void sort_voxels_by_z()
-
virtual void updateBuffers() const override
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 mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const override
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>
inline void setFromOctoMap(OCTOMAP &m) Sets the contents of the object from a mrpt::maps::COctoMap object.
Note
Declared as a template because in the library [mrpt-opengl] we don’t have access to the library [mrpt-maps].
- Template Parameters:
Typically, an – mrpt::maps::COctoMap object
-
COctoMapVoxels()
Constructor
-
~COctoMapVoxels() override = default
Private, virtual destructor: only can be deleted from smart pointers.
Protected Attributes
-
std::deque<TInfoPerVoxelSet> m_voxel_sets
-
mrpt::math::TPoint3D m_bb_min
Cached bounding boxes
-
mrpt::math::TPoint3D m_bb_max
-
bool m_enable_lighting = {false}
-
bool m_enable_cube_transparency = {true}
-
bool m_showVoxelsAsPoints = {false}
-
float m_showVoxelsAsPointsSize = {3.0f}
-
bool m_show_grids = {false}
-
float m_grid_width = {1.0f}
-
mrpt::img::TColor m_grid_color
-
visualization_mode_t m_visual_mode = {COctoMapVoxels::COLOR_FROM_OCCUPANCY}
-
mrpt::img::TColormap m_color_map = mrpt::img::cmHOT
-
struct TGridCube
The info of each grid block