10#ifndef opengl_COctoMapVoxels_H
11#define opengl_COctoMapVoxels_H
146 inline bool areVoxelsVisible(
unsigned int voxel_set)
const {
ASSERT_(voxel_set<m_voxel_sets.size())
return m_voxel_sets[voxel_set].visible; }
169 inline size_t getVoxelCount(
const size_t set_index)
const {
ASSERT_(set_index<m_voxel_sets.size())
return m_voxel_sets[set_index].voxels.size(); }
203 template <class OCTOMAP>
204 void setFromOctoMap(OCTOMAP &m) {
205 m.getAsOctoMapVoxels(*
this);
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void showGridLines(bool show)
Shows/hides the grid lines.
visualization_mode_t getVisualizationMode() const
visualization_mode_t m_visual_mode
void setVoxelAsPointsSize(float pointSize)
Only used when showVoxelsAsPoints() is enabled.
const TVoxel & getVoxel(const size_t set_index, const size_t idx) const
void showVoxelsAsPoints(const bool enable)
For quick renders: render voxels as points instead of cubes.
bool areVoxelsShownAsPoints() const
void push_back_Voxel(const size_t set_index, const TVoxel &v)
bool areVoxelsVisible(unsigned int voxel_set) const
void resizeGridCubes(const size_t nCubes)
TGridCube & getGridCubeRef(const size_t idx)
void enableLights(bool enable)
Can be used to enable/disable the effects of lighting in this object.
size_t getVoxelSetCount() const
Returns the number of voxel sets.
bool isCubeTransparencyEnabled() const
const TGridCube & getGridCube(const size_t idx) const
mrpt::utils::TColor m_grid_color
float getGridLinesWidth() const
Gets the width of grid lines.
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)
mrpt::math::TPoint3D m_bb_max
Cached bounding boxes.
bool areLightsEnabled() const
virtual ~COctoMapVoxels()
Private, virtual destructor: only can be deleted from smart pointers.
float m_showVoxelsAsPointsSize
size_t getVoxelCount(const size_t set_index) const
Returns the total count of voxels in one voxel set.
void enableCubeTransparency(bool enable)
By default, the alpha (transparency) component of voxel cubes is taken into account,...
bool m_enable_cube_transparency
COctoMapVoxels()
Constructor.
float getVoxelAsPointsSize() const
visualization_mode_t
The different coloring schemes, which modulate the generic mrpt::opengl::CRenderizable object color.
@ MIXED
Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY.
@ TRANSPARENCY_FROM_OCCUPANCY
Transparency goes from opaque (occupied voxel) to transparent (free voxel).
@ TRANS_AND_COLOR_FROM_OCCUPANCY
Color goes from black (occupaid voxel) to the chosen color (free voxel) and they are transparent.
@ COLOR_FROM_OCCUPANCY
Color goes from black (occupied voxel) to the chosen color (free voxel)
@ COLOR_FROM_HEIGHT
Color goes from black (at the bottom) to the chosen color (at the top)
std::vector< TGridCube > m_grid_cubes
std::deque< TInfoPerVoxelSet > m_voxel_sets
void setGridLinesWidth(float w)
Sets the width of grid lines.
void reserveVoxels(const size_t set_index, const size_t nVoxels)
void setGridLinesColor(const mrpt::utils::TColor &color)
void setVisualizationMode(visualization_mode_t mode)
Select the visualization mode.
void render_dl() const MRPT_OVERRIDE
Render.
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,...
bool m_showVoxelsAsPoints
void reserveGridCubes(const size_t nCubes)
const mrpt::utils::TColor & getGridLinesColor() const
bool areGridLinesVisible() const
void resizeVoxelSets(const size_t nVoxelSets)
void push_back_GridCube(const TGridCube &c)
TVoxel & getVoxelRef(const size_t set_index, const size_t idx)
void clear()
Clears everything.
void resizeVoxels(const size_t set_index, const size_t nVoxels)
size_t getGridCubeCount() const
Returns the total count of grid cubes.
A renderizable object suitable for rendering with OpenGL's display lists.
EIGEN_STRONG_INLINE void notifyChange() const
Must be called to notify that the object has changed (so, the display list must be updated)
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
The info of each grid block.
mrpt::math::TPoint3D max
opposite corners of the cube
TGridCube(const mrpt::math::TPoint3D &min_, const mrpt::math::TPoint3D &max_)
std::vector< TVoxel > voxels
The info of each of the voxels.
mrpt::utils::TColor color
mrpt::math::TPoint3D coords
TVoxel(const mrpt::math::TPoint3D &coords_, const double side_length_, mrpt::utils::TColor color_)