MRPT  1.9.9
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-2018, 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 #pragma once
10 
13 
14 namespace mrpt::opengl
15 {
17 {
20 };
21 
22 /** A flexible renderer of voxels, typically from a 3D octo map (see
23  *mrpt::maps::COctoMap).
24  * This class is sort of equivalent to octovis::OcTreeDrawer from the octomap
25  *package, but
26  * relying on MRPT's CRenderizableDisplayList so there's no need to manually
27  *cache the rendering of OpenGL primitives.
28  *
29  * Normally users call mrpt::maps::COctoMap::getAs3DObject() to obtain a
30  *generic mrpt::opengl::CSetOfObjects which insides holds an instance of
31  *COctoMapVoxels.
32  * You can also alternativelly call COctoMapVoxels::setFromOctoMap(), so you
33  *can tune the display parameters, colors, etc.
34  * As with any other mrpt::opengl class, all object coordinates refer to some
35  *frame of reference which is relative to the object parent and can be changed
36  *with mrpt::opengl::CRenderizable::setPose()
37  *
38  * This class draws these separate elements to represent an OctoMap:
39  * - A grid representation of all cubes, as simple lines (occupied/free,
40  *leafs/nodes,... whatever). See:
41  * - showGridLines()
42  * - setGridLinesColor()
43  * - setGridLinesWidth()
44  * - push_back_GridCube()
45  * - A number of <b>voxel collections</b>, drawn as cubes each having a
46  *different color (e.g. depending on the color scheme in the original
47  *mrpt::maps::COctoMap object).
48  * The meanning of each collection is user-defined, but you can use the
49  *constants VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE for predefined meanings.
50  * - showVoxels()
51  * - push_back_Voxel()
52  *
53  * Several coloring schemes can be selected with setVisualizationMode(). See
54  *COctoMapVoxels::visualization_mode_t
55  *
56  * <div align="center">
57  * <table border="0" cellspan="4" cellspacing="4" style="border-width: 1px;
58  *border-style: solid;">
59  * <tr> <td> mrpt::opengl::COctoMapVoxels </td> <td> \image html
60  *preview_COctoMapVoxels.png </td> </tr>
61  * </table>
62  * </div>
63  *
64  * \sa opengl::COpenGLScene
65  * \ingroup mrpt_opengl_grp
66  */
68 {
70  public:
71  /** The different coloring schemes, which modulate the generic
72  * mrpt::opengl::CRenderizable object color. Set with setVisualizationMode()
73  */
75  {
76  /** Color goes from black (at the bottom) to the chosen color (at the
77  top) */
79  /** Color goes from black (occupied voxel) to the chosen color (free
80  voxel) */
82  /** Transparency goes from opaque (occupied voxel) to transparent (free
83  voxel). */
85  /** Color goes from black (occupaid voxel) to the chosen color (free
86  voxel) and they are transparent */
88  /** Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY */
90  /** All cubes are of identical color. */
92  };
93 
94  /** The info of each of the voxels */
95  struct TVoxel
96  {
98  double side_length;
100 
101  TVoxel() {}
103  const mrpt::math::TPoint3D& coords_, const double side_length_,
104  mrpt::img::TColor color_)
105  : coords(coords_), side_length(side_length_), color(color_)
106  {
107  }
108  };
109 
110  /** The info of each grid block */
111  struct TGridCube
112  {
113  /** opposite corners of the cube */
115 
118  const mrpt::math::TPoint3D& min_, const mrpt::math::TPoint3D& max_)
119  : min(min_), max(max_)
120  {
121  }
122  };
123 
125  {
126  bool visible;
127  std::vector<TVoxel> voxels;
128 
130  };
131 
132  protected:
133  std::deque<TInfoPerVoxelSet> m_voxel_sets;
134  std::vector<TGridCube> m_grid_cubes;
135 
136  /** Cached bounding boxes */
138 
147 
148  public:
149  /** Clears everything */
150  void clear();
151 
152  /** Select the visualization mode. To have any effect, this method has to be
153  * called before loading the octomap. */
155  {
158  }
160  {
161  return m_visual_mode;
162  }
163 
164  /** Can be used to enable/disable the effects of lighting in this object */
165  inline void enableLights(bool enable)
166  {
167  m_enable_lighting = enable;
169  }
170  inline bool areLightsEnabled() const { return m_enable_lighting; }
171  /** By default, the alpha (transparency) component of voxel cubes is taken
172  * into account, but transparency can be disabled with this method. */
173  inline void enableCubeTransparency(bool enable)
174  {
177  }
178  inline bool isCubeTransparencyEnabled() const
179  {
181  }
182 
183  /** Shows/hides the grid lines */
184  inline void showGridLines(bool show)
185  {
186  m_show_grids = show;
188  }
189  inline bool areGridLinesVisible() const { return m_show_grids; }
190  /** Shows/hides the voxels (voxel_set is a 0-based index for the set of
191  * voxels to modify, e.g. VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE) */
192  inline void showVoxels(unsigned int voxel_set, bool show)
193  {
194  ASSERT_(voxel_set < m_voxel_sets.size());
195  m_voxel_sets[voxel_set].visible = show;
197  }
198  inline bool areVoxelsVisible(unsigned int voxel_set) const
199  {
200  ASSERT_(voxel_set < m_voxel_sets.size());
201  return m_voxel_sets[voxel_set].visible;
202  }
203 
204  /** For quick renders: render voxels as points instead of cubes. \sa
205  * setVoxelAsPointsSize */
206  inline void showVoxelsAsPoints(const bool enable)
207  {
208  m_showVoxelsAsPoints = enable;
210  }
211  inline bool areVoxelsShownAsPoints() const { return m_showVoxelsAsPoints; }
212  /** Only used when showVoxelsAsPoints() is enabled. */
213  inline void setVoxelAsPointsSize(float pointSize)
214  {
215  m_showVoxelsAsPointsSize = pointSize;
217  }
218  inline float getVoxelAsPointsSize() const
219  {
221  }
222 
223  /** Sets the width of grid lines */
224  inline void setGridLinesWidth(float w)
225  {
226  m_grid_width = w;
228  }
229  /** Gets the width of grid lines */
230  inline float getGridLinesWidth() const { return m_grid_width; }
232  {
235  }
236  inline const mrpt::img::TColor& getGridLinesColor() const
237  {
238  return m_grid_color;
239  }
240 
241  /** Returns the total count of grid cubes. */
242  inline size_t getGridCubeCount() const { return m_grid_cubes.size(); }
243  /** Returns the number of voxel sets. */
244  inline size_t getVoxelSetCount() const { return m_voxel_sets.size(); }
245  /** Returns the total count of voxels in one voxel set. */
246  inline size_t getVoxelCount(const size_t set_index) const
247  {
248  ASSERT_(set_index < m_voxel_sets.size());
249  return m_voxel_sets[set_index].voxels.size();
250  }
251 
252  /** Manually changes the bounding box (normally the user doesn't need to
253  * call this) */
254  void setBoundingBox(
255  const mrpt::math::TPoint3D& bb_min, const mrpt::math::TPoint3D& bb_max);
256 
257  inline void resizeGridCubes(const size_t nCubes)
258  {
259  m_grid_cubes.resize(nCubes);
261  }
262  inline void resizeVoxelSets(const size_t nVoxelSets)
263  {
264  m_voxel_sets.resize(nVoxelSets);
266  }
267  inline void resizeVoxels(const size_t set_index, const size_t nVoxels)
268  {
269  ASSERT_(set_index < m_voxel_sets.size());
270  m_voxel_sets[set_index].voxels.resize(nVoxels);
272  }
273 
274  inline void reserveGridCubes(const size_t nCubes)
275  {
276  m_grid_cubes.reserve(nCubes);
277  }
278  inline void reserveVoxels(const size_t set_index, const size_t nVoxels)
279  {
280  ASSERT_(set_index < m_voxel_sets.size());
281  m_voxel_sets[set_index].voxels.reserve(nVoxels);
283  }
284 
285  inline TGridCube& getGridCubeRef(const size_t idx)
286  {
287  ASSERTDEB_(idx < m_grid_cubes.size());
289  return m_grid_cubes[idx];
290  }
291  inline const TGridCube& getGridCube(const size_t idx) const
292  {
293  ASSERTDEB_(idx < m_grid_cubes.size());
294  return m_grid_cubes[idx];
295  }
296 
297  inline TVoxel& getVoxelRef(const size_t set_index, const size_t idx)
298  {
299  ASSERTDEB_(
300  set_index < m_voxel_sets.size() &&
301  idx < m_voxel_sets[set_index].voxels.size());
303  return m_voxel_sets[set_index].voxels[idx];
304  }
305  inline const TVoxel& getVoxel(
306  const size_t set_index, const size_t idx) const
307  {
308  ASSERTDEB_(
309  set_index < m_voxel_sets.size() &&
310  idx < m_voxel_sets[set_index].voxels.size());
312  return m_voxel_sets[set_index].voxels[idx];
313  }
314 
315  inline void push_back_GridCube(const TGridCube& c)
316  {
318  m_grid_cubes.push_back(c);
319  }
320  inline void push_back_Voxel(const size_t set_index, const TVoxel& v)
321  {
322  ASSERTDEB_(set_index < m_voxel_sets.size());
324  m_voxel_sets[set_index].voxels.push_back(v);
325  }
326 
327  void sort_voxels_by_z();
328 
329  /** Render */
330  void render_dl() const override;
331 
332  /** Evaluates the bounding box of this object (including possible children)
333  * in the coordinate frame of the object parent. */
334  void getBoundingBox(
335  mrpt::math::TPoint3D& bb_min,
336  mrpt::math::TPoint3D& bb_max) const override;
337 
338  /** Sets the contents of the object from a mrpt::maps::COctoMap object.
339  * \tparam Typically, an mrpt::maps::COctoMap object
340  *
341  * \note Declared as a template because in the library [mrpt-opengl] we
342  * don't have access to the library [mrpt-maps].
343  */
344  template <class OCTOMAP>
345  void setFromOctoMap(OCTOMAP& m)
346  {
347  m.getAsOctoMapVoxels(*this);
348  }
349 
350  /** Constructor */
351  COctoMapVoxels();
352  /** Private, virtual destructor: only can be deleted from smart pointers. */
353  virtual ~COctoMapVoxels() {}
354 };
355 
356 }
357 
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.
mrpt::img::TColor m_grid_color
void reserveVoxels(const size_t set_index, const size_t nVoxels)
TGridCube & getGridCubeRef(const size_t idx)
const GLshort * coords
Definition: glext.h:7386
All cubes are of identical color.
visualization_mode_t
The different coloring schemes, which modulate the generic mrpt::opengl::CRenderizable object color...
bool areVoxelsVisible(unsigned int voxel_set) const
const TGridCube & getGridCube(const size_t idx) const
void enableLights(bool enable)
Can be used to enable/disable the effects of lighting in this object.
mrpt::math::TPoint3D m_bb_min
Cached bounding boxes.
std::deque< TInfoPerVoxelSet > m_voxel_sets
void setFromOctoMap(OCTOMAP &m)
Sets the contents of the object from a mrpt::maps::COctoMap object.
void setVoxelAsPointsSize(float pointSize)
Only used when showVoxelsAsPoints() is enabled.
mrpt::math::TPoint3D m_bb_max
size_t getVoxelCount(const size_t set_index) const
Returns the total count of voxels in one voxel set.
TVoxel & getVoxelRef(const size_t set_index, const size_t idx)
Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY.
TVoxel(const mrpt::math::TPoint3D &coords_, const double side_length_, mrpt::img::TColor color_)
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.
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&#39;t need to call this)
Color goes from black (at the bottom) to the chosen color (at the top)
size_t getVoxelSetCount() const
Returns the number of voxel sets.
void reserveGridCubes(const size_t nCubes)
EIGEN_STRONG_INLINE void notifyChange() const
Must be called to notify that the object has changed (so, the display list must be updated) ...
Transparency goes from opaque (occupied voxel) to transparent (free voxel).
void clear()
Clears everything.
void resizeVoxels(const size_t set_index, const size_t nVoxels)
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
A renderizable object suitable for rendering with OpenGL&#39;s display lists.
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
GLuint color
Definition: glext.h:8300
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:113
void push_back_GridCube(const TGridCube &c)
const GLubyte * c
Definition: glext.h:6313
Color goes from black (occupaid voxel) to the chosen color (free voxel) and they are transparent...
size_t getGridCubeCount() const
Returns the total count of grid cubes.
void render_dl() const override
Render.
void setGridLinesColor(const mrpt::img::TColor &color)
const TVoxel & getVoxel(const size_t set_index, const size_t idx) const
const mrpt::img::TColor & getGridLinesColor() const
The info of each grid block.
void push_back_Voxel(const size_t set_index, const TVoxel &v)
GLint mode
Definition: glext.h:5669
The info of each of the voxels.
const GLdouble * v
Definition: glext.h:3678
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Color goes from black (occupied voxel) to the chosen color (free voxel)
void getBoundingBox(mrpt::math::TPoint3D &bb_min, mrpt::math::TPoint3D &bb_max) const override
Evaluates the bounding box of this object (including possible children) in the coordinate frame of th...
visualization_mode_t m_visual_mode
void showVoxelsAsPoints(const bool enable)
For quick renders: render voxels as points instead of cubes.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: exceptions.h:205
void resizeVoxelSets(const size_t nVoxelSets)
visualization_mode_t getVisualizationMode() const
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
void showGridLines(bool show)
Shows/hides the grid lines.
void setVisualizationMode(visualization_mode_t mode)
Select the visualization mode.
std::vector< TGridCube > m_grid_cubes
A RGB color - 8bit.
Definition: TColor.h:20
Lightweight 3D point.
void resizeGridCubes(const size_t nCubes)
bool isCubeTransparencyEnabled() const
virtual ~COctoMapVoxels()
Private, virtual destructor: only can be deleted from smart pointers.
mrpt::math::TPoint3D min
opposite corners of the cube
void setGridLinesWidth(float w)
Sets the width of grid lines.
TGridCube(const mrpt::math::TPoint3D &min_, const mrpt::math::TPoint3D &max_)



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020