Main MRPT website > C++ reference for MRPT 1.4.0
COctoMapVoxels.h
Go to the documentation of this file.
1/* +---------------------------------------------------------------------------+
2 | Mobile Robot Programming Toolkit (MRPT) |
3 | http://www.mrpt.org/ |
4 | |
5 | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6 | See: http://www.mrpt.org/Authors - All rights reserved. |
7 | Released under BSD License. See details in http://www.mrpt.org/License |
8 +---------------------------------------------------------------------------+ */
9
10#ifndef opengl_COctoMapVoxels_H
11#define opengl_COctoMapVoxels_H
12
15
16namespace mrpt
17{
18 namespace opengl
19 {
21 {
24 };
25
26 // This must be added to any CSerializable derived class:
28
29 /** A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
30 * This class is sort of equivalent to octovis::OcTreeDrawer from the octomap package, but
31 * relying on MRPT's CRenderizableDisplayList so there's no need to manually cache the rendering of OpenGL primitives.
32 *
33 * Normally users call mrpt::maps::COctoMap::getAs3DObject() to obtain a generic mrpt::opengl::CSetOfObjects which insides holds an instance of COctoMapVoxels.
34 * You can also alternativelly call COctoMapVoxels::setFromOctoMap(), so you can tune the display parameters, colors, etc.
35 * 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()
36 *
37 * This class draws these separate elements to represent an OctoMap:
38 * - A grid representation of all cubes, as simple lines (occupied/free, leafs/nodes,... whatever). See:
39 * - showGridLines()
40 * - setGridLinesColor()
41 * - setGridLinesWidth()
42 * - push_back_GridCube()
43 * - A number of <b>voxel collections</b>, drawn as cubes each having a different color (e.g. depending on the color scheme in the original mrpt::maps::COctoMap object).
44 * The meanning of each collection is user-defined, but you can use the constants VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE for predefined meanings.
45 * - showVoxels()
46 * - push_back_Voxel()
47 *
48 * Several coloring schemes can be selected with setVisualizationMode(). See COctoMapVoxels::visualization_mode_t
49 *
50 * <div align="center">
51 * <table border="0" cellspan="4" cellspacing="4" style="border-width: 1px; border-style: solid;">
52 * <tr> <td> mrpt::opengl::COctoMapVoxels </td> <td> \image html preview_COctoMapVoxels.png </td> </tr>
53 * </table>
54 * </div>
55 *
56 * \sa opengl::COpenGLScene
57 * \ingroup mrpt_opengl_grp
58 */
60 {
62 public:
63
64 /** The different coloring schemes, which modulate the generic mrpt::opengl::CRenderizable object color. Set with setVisualizationMode() */
66 {
67 COLOR_FROM_HEIGHT, //!< Color goes from black (at the bottom) to the chosen color (at the top)
68 COLOR_FROM_OCCUPANCY, //!< Color goes from black (occupied voxel) to the chosen color (free voxel)
69 TRANSPARENCY_FROM_OCCUPANCY, //!< Transparency goes from opaque (occupied voxel) to transparent (free voxel).
70 TRANS_AND_COLOR_FROM_OCCUPANCY, //!< Color goes from black (occupaid voxel) to the chosen color (free voxel) and they are transparent
71 MIXED, //!< Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY
72 FIXED //!< All cubes are of identical color.
73 };
74
75
76 /** The info of each of the voxels */
78 {
82
83 TVoxel() {}
84 TVoxel(const mrpt::math::TPoint3D &coords_, const double side_length_, mrpt::utils::TColor color_) : coords(coords_), side_length(side_length_),color(color_) {}
85 };
86
87 /** The info of each grid block */
89 {
90 mrpt::math::TPoint3D min,max; //!< opposite corners of the cube
91
93 TGridCube(const mrpt::math::TPoint3D &min_,const mrpt::math::TPoint3D &max_) : min(min_),max(max_) { }
94 };
95
97 {
98 bool visible;
99 std::vector<TVoxel> voxels;
100
101 TInfoPerVoxelSet() : visible(true) {}
102 };
103 protected:
104
105 std::deque<TInfoPerVoxelSet> m_voxel_sets;
106 std::vector<TGridCube> m_grid_cubes;
107
108 mrpt::math::TPoint3D m_bb_min, m_bb_max; //!< Cached bounding boxes
109
118
119 public:
120
121 /** Clears everything */
122 void clear();
123
124 /** Select the visualization mode. To have any effect, this method has to be called before loading the octomap. */
126 m_visual_mode = mode; CRenderizableDisplayList::notifyChange();
127 }
128 inline visualization_mode_t getVisualizationMode() const {return m_visual_mode;}
129
130 /** Can be used to enable/disable the effects of lighting in this object */
131 inline void enableLights(bool enable) { m_enable_lighting=enable; CRenderizableDisplayList::notifyChange(); }
132 inline bool areLightsEnabled() const { return m_enable_lighting; }
133
134
135
136 /** By default, the alpha (transparency) component of voxel cubes is taken into account, but transparency can be disabled with this method. */
137 inline void enableCubeTransparency(bool enable) { m_enable_cube_transparency=enable; CRenderizableDisplayList::notifyChange(); }
138 inline bool isCubeTransparencyEnabled() const { return m_enable_cube_transparency; }
139
140 /** Shows/hides the grid lines */
141 inline void showGridLines(bool show) { m_show_grids=show; CRenderizableDisplayList::notifyChange(); }
142 inline bool areGridLinesVisible() const { return m_show_grids; }
143
144 /** 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) */
145 inline void showVoxels(unsigned int voxel_set, bool show) { ASSERT_(voxel_set<m_voxel_sets.size()) m_voxel_sets[voxel_set].visible=show; CRenderizableDisplayList::notifyChange(); }
146 inline bool areVoxelsVisible(unsigned int voxel_set) const { ASSERT_(voxel_set<m_voxel_sets.size()) return m_voxel_sets[voxel_set].visible; }
147
148 /** For quick renders: render voxels as points instead of cubes. \sa setVoxelAsPointsSize */
149 inline void showVoxelsAsPoints(const bool enable) { m_showVoxelsAsPoints=enable; CRenderizableDisplayList::notifyChange(); }
150 inline bool areVoxelsShownAsPoints() const { return m_showVoxelsAsPoints; }
151
152 /** Only used when showVoxelsAsPoints() is enabled. */
153 inline void setVoxelAsPointsSize(float pointSize) { m_showVoxelsAsPointsSize=pointSize; CRenderizableDisplayList::notifyChange(); }
154 inline float getVoxelAsPointsSize() const { return m_showVoxelsAsPointsSize; }
155
156 /** Sets the width of grid lines */
157 inline void setGridLinesWidth(float w) { m_grid_width=w; CRenderizableDisplayList::notifyChange(); }
158 /** Gets the width of grid lines */
159 inline float getGridLinesWidth() const { return m_grid_width; }
160
161 inline void setGridLinesColor(const mrpt::utils::TColor &color) { m_grid_color=color; CRenderizableDisplayList::notifyChange(); }
162 inline const mrpt::utils::TColor & getGridLinesColor() const { return m_grid_color; }
163
164 /** Returns the total count of grid cubes. */
165 inline size_t getGridCubeCount() const { return m_grid_cubes.size(); }
166 /** Returns the number of voxel sets. */
167 inline size_t getVoxelSetCount() const { return m_voxel_sets.size(); }
168 /** Returns the total count of voxels in one voxel set. */
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(); }
170
171 /** Manually changes the bounding box (normally the user doesn't need to call this) */
172 void setBoundingBox(const mrpt::math::TPoint3D &bb_min, const mrpt::math::TPoint3D &bb_max);
173
174 inline void resizeGridCubes(const size_t nCubes) { m_grid_cubes.resize(nCubes); CRenderizableDisplayList::notifyChange(); }
175 inline void resizeVoxelSets(const size_t nVoxelSets) { m_voxel_sets.resize(nVoxelSets); CRenderizableDisplayList::notifyChange(); }
176 inline void resizeVoxels(const size_t set_index, const size_t nVoxels) { ASSERT_(set_index<m_voxel_sets.size()) m_voxel_sets[set_index].voxels.resize(nVoxels); CRenderizableDisplayList::notifyChange(); }
177
178 inline void reserveGridCubes(const size_t nCubes) { m_grid_cubes.reserve(nCubes); }
179 inline void reserveVoxels(const size_t set_index, const size_t nVoxels) { ASSERT_(set_index<m_voxel_sets.size()) m_voxel_sets[set_index].voxels.reserve(nVoxels); CRenderizableDisplayList::notifyChange(); }
180
181 inline TGridCube & getGridCubeRef(const size_t idx) { ASSERTDEB_(idx<m_grid_cubes.size()) CRenderizableDisplayList::notifyChange(); return m_grid_cubes[idx]; }
182 inline const TGridCube & getGridCube(const size_t idx) const { ASSERTDEB_(idx<m_grid_cubes.size()) return m_grid_cubes[idx]; }
183
184 inline TVoxel & getVoxelRef(const size_t set_index, const size_t idx) { ASSERTDEB_(set_index<m_voxel_sets.size() && idx<m_voxel_sets[set_index].voxels.size()) CRenderizableDisplayList::notifyChange(); return m_voxel_sets[set_index].voxels[idx]; }
185 inline const TVoxel & getVoxel(const size_t set_index, const size_t idx) const { ASSERTDEB_(set_index<m_voxel_sets.size() && idx<m_voxel_sets[set_index].voxels.size()) CRenderizableDisplayList::notifyChange(); return m_voxel_sets[set_index].voxels[idx]; }
186
187 inline void push_back_GridCube(const TGridCube & c) { CRenderizableDisplayList::notifyChange(); m_grid_cubes.push_back(c); }
188 inline void push_back_Voxel(const size_t set_index, const TVoxel & v) { ASSERTDEB_(set_index<m_voxel_sets.size()) CRenderizableDisplayList::notifyChange(); m_voxel_sets[set_index].voxels.push_back(v); }
189
191
192 /** Render */
194
195 /** Evaluates the bounding box of this object (including possible children) in the coordinate frame of the object parent. */
196 void getBoundingBox(mrpt::math::TPoint3D &bb_min, mrpt::math::TPoint3D &bb_max) const MRPT_OVERRIDE;
197
198 /** Sets the contents of the object from a mrpt::maps::COctoMap object.
199 * \tparam Typically, an mrpt::maps::COctoMap object
200 *
201 * \note Declared as a template because in the library [mrpt-opengl] we don't have access to the library [mrpt-maps].
202 */
203 template <class OCTOMAP>
204 void setFromOctoMap(OCTOMAP &m) {
205 m.getAsOctoMapVoxels(*this);
206 }
207
208 private:
209 /** Constructor */
211 /** Private, virtual destructor: only can be deleted from smart pointers. */
212 virtual ~COctoMapVoxels() { }
213 };
214 DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE( COctoMapVoxels, CRenderizableDisplayList, OPENGL_IMPEXP )
215
216 } // end namespace
217} // End of namespace
218
219#endif
#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.
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.
virtual ~COctoMapVoxels()
Private, virtual destructor: only can be deleted from smart pointers.
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,...
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,...
void reserveGridCubes(const size_t nCubes)
const mrpt::utils::TColor & getGridLinesColor() 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 ASSERT_(f)
Definition: mrpt_macros.h:261
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: mrpt_macros.h:283
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Definition: mrpt_macros.h:28
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Lightweight 3D point.
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_)
The info of each of the voxels.
TVoxel(const mrpt::math::TPoint3D &coords_, const double side_length_, mrpt::utils::TColor color_)
A RGB color - 8bit.
Definition: TColor.h:26



Page generated by Doxygen 1.9.6 for MRPT 1.4.0 SVN: at Wed Mar 22 09:54:56 UTC 2023