MRPT  2.0.4
COctoMapVoxels.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/math/TPoint3D.h>
15 
16 namespace mrpt::opengl
17 {
19 {
22 };
23 
24 /** A flexible renderer of voxels, typically from a 3D octo map (see
25  *mrpt::maps::COctoMap).
26  * This class is sort of equivalent to octovis::OcTreeDrawer from the octomap
27  *package, but
28  * relying on MRPT's CRenderizable so there's no need to manually
29  *cache the rendering of OpenGL primitives.
30  *
31  * Normally users call mrpt::maps::COctoMap::getAs3DObject() to obtain a
32  *generic mrpt::opengl::CSetOfObjects which insides holds an instance of
33  *COctoMapVoxels.
34  * You can also alternativelly call COctoMapVoxels::setFromOctoMap(), so you
35  *can tune the display parameters, colors, etc.
36  * As with any other mrpt::opengl class, all object coordinates refer to some
37  *frame of reference which is relative to the object parent and can be changed
38  *with mrpt::opengl::CRenderizable::setPose()
39  *
40  * This class draws these separate elements to represent an OctoMap:
41  * - A grid representation of all cubes, as simple lines (occupied/free,
42  *leafs/nodes,... whatever). See:
43  * - showGridLines()
44  * - setGridLinesColor()
45  * - setGridLinesWidth()
46  * - push_back_GridCube()
47  * - A number of <b>voxel collections</b>, drawn as cubes each having a
48  *different color (e.g. depending on the color scheme in the original
49  *mrpt::maps::COctoMap object).
50  * The meanning of each collection is user-defined, but you can use the
51  *constants VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE for predefined meanings.
52  * - showVoxels()
53  * - push_back_Voxel()
54  *
55  * Several coloring schemes can be selected with setVisualizationMode(). See
56  *COctoMapVoxels::visualization_mode_t
57  *
58  * <div align="center">
59  * <table border="0" cellspan="4" cellspacing="4" style="border-width: 1px;
60  *border-style: solid;">
61  * <tr> <td> mrpt::opengl::COctoMapVoxels </td> <td> \image html
62  *preview_COctoMapVoxels.png </td> </tr>
63  * </table>
64  * </div>
65  *
66  * \sa opengl::COpenGLScene
67  * \ingroup mrpt_opengl_grp
68  */
72 {
74  public:
75  /** The different coloring schemes, which modulate the generic
76  * mrpt::opengl::CRenderizable object color. Set with setVisualizationMode()
77  */
79  {
80  /** Color goes from black (at the bottom) to the chosen color (at the
81  top) */
83  /** Color goes from black (occupied voxel) to the chosen color (free
84  voxel) */
86  /** Transparency goes from opaque (occupied voxel) to transparent (free
87  voxel). */
89  /** Color goes from black (occupaid voxel) to the chosen color (free
90  voxel) and they are transparent */
92  /** Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY */
94  /** All cubes are of identical color. */
96  };
97 
98  /** The info of each of the voxels */
99  struct TVoxel
100  {
102  double side_length;
104 
105  TVoxel() = default;
107  const mrpt::math::TPoint3Df& coords_, const double side_length_,
108  mrpt::img::TColor color_)
109  : coords(coords_), side_length(side_length_), color(color_)
110  {
111  }
112  };
113 
114  /** The info of each grid block */
115  struct TGridCube
116  {
117  /** opposite corners of the cube */
119 
120  TGridCube() = default;
122  const mrpt::math::TPoint3Df& min_,
123  const mrpt::math::TPoint3Df& max_)
124  : min(min_), max(max_)
125  {
126  }
127  };
128 
130  {
131  bool visible{true};
132  std::vector<TVoxel> voxels;
133 
134  TInfoPerVoxelSet() = default;
135  };
136 
137  protected:
138  std::deque<TInfoPerVoxelSet> m_voxel_sets;
139  std::vector<TGridCube> m_grid_cubes;
140 
141  /** Cached bounding boxes */
143 
144  bool m_enable_lighting{false};
146  bool m_showVoxelsAsPoints{false};
148  bool m_show_grids{false};
149  float m_grid_width{1.0f};
152 
153  public:
154  /** @name Renderizable shader API virtual methods
155  * @{ */
156  void render(const RenderContext& rc) const override;
157  void renderUpdateBuffers() const override;
158 
159  virtual shader_list_t requiredShaders() const override
160  {
161  // May use up to two shaders (triangles and lines):
164  }
165  void onUpdateBuffers_Points() override;
166  void onUpdateBuffers_Wireframe() override;
167  void onUpdateBuffers_Triangles() override;
168  void freeOpenGLResources() override
169  {
173  }
174  /** @} */
175 
176  /** Clears everything */
177  void clear();
178 
179  /** Select the visualization mode. To have any effect, this method has to be
180  * called before loading the octomap. */
182  {
183  m_visual_mode = mode;
185  }
187  {
188  return m_visual_mode;
189  }
190 
191  /** Can be used to enable/disable the effects of lighting in this object */
192  inline void enableLights(bool enable)
193  {
194  m_enable_lighting = enable;
196  }
197  inline bool areLightsEnabled() const { return m_enable_lighting; }
198  /** By default, the alpha (transparency) component of voxel cubes is taken
199  * into account, but transparency can be disabled with this method. */
200  inline void enableCubeTransparency(bool enable)
201  {
204  }
205  inline bool isCubeTransparencyEnabled() const
206  {
208  }
209 
210  /** Shows/hides the grid lines */
211  inline void showGridLines(bool show)
212  {
213  m_show_grids = show;
215  }
216  inline bool areGridLinesVisible() const { return m_show_grids; }
217  /** Shows/hides the voxels (voxel_set is a 0-based index for the set of
218  * voxels to modify, e.g. VOXEL_SET_OCCUPIED, VOXEL_SET_FREESPACE) */
219  inline void showVoxels(unsigned int voxel_set, bool show)
220  {
221  ASSERT_(voxel_set < m_voxel_sets.size());
222  m_voxel_sets[voxel_set].visible = show;
224  }
225  inline bool areVoxelsVisible(unsigned int voxel_set) const
226  {
227  ASSERT_(voxel_set < m_voxel_sets.size());
228  return m_voxel_sets[voxel_set].visible;
229  }
230 
231  /** For quick renders: render voxels as points instead of cubes. \sa
232  * setVoxelAsPointsSize */
233  inline void showVoxelsAsPoints(const bool enable)
234  {
235  m_showVoxelsAsPoints = enable;
237  }
238  inline bool areVoxelsShownAsPoints() const { return m_showVoxelsAsPoints; }
239  /** Only used when showVoxelsAsPoints() is enabled. */
240  inline void setVoxelAsPointsSize(float pointSize)
241  {
242  m_showVoxelsAsPointsSize = pointSize;
244  }
245  inline float getVoxelAsPointsSize() const
246  {
248  }
249 
250  /** Sets the width of grid lines */
251  inline void setGridLinesWidth(float w)
252  {
253  m_grid_width = w;
255  }
256  /** Gets the width of grid lines */
257  inline float getGridLinesWidth() const { return m_grid_width; }
258  inline void setGridLinesColor(const mrpt::img::TColor& color)
259  {
260  m_grid_color = color;
262  }
263  inline const mrpt::img::TColor& getGridLinesColor() const
264  {
265  return m_grid_color;
266  }
267 
268  /** Returns the total count of grid cubes. */
269  inline size_t getGridCubeCount() const { return m_grid_cubes.size(); }
270  /** Returns the number of voxel sets. */
271  inline size_t getVoxelSetCount() const { return m_voxel_sets.size(); }
272  /** Returns the total count of voxels in one voxel set. */
273  inline size_t getVoxelCount(const size_t set_index) const
274  {
275  ASSERT_(set_index < m_voxel_sets.size());
276  return m_voxel_sets[set_index].voxels.size();
277  }
278 
279  /** Manually changes the bounding box (normally the user doesn't need to
280  * call this) */
281  void setBoundingBox(
283 
284  inline void resizeGridCubes(const size_t nCubes)
285  {
286  m_grid_cubes.resize(nCubes);
288  }
289  inline void resizeVoxelSets(const size_t nVoxelSets)
290  {
291  m_voxel_sets.resize(nVoxelSets);
293  }
294  inline void resizeVoxels(const size_t set_index, const size_t nVoxels)
295  {
296  ASSERT_(set_index < m_voxel_sets.size());
297  m_voxel_sets[set_index].voxels.resize(nVoxels);
299  }
300 
301  inline void reserveGridCubes(const size_t nCubes)
302  {
303  m_grid_cubes.reserve(nCubes);
304  }
305  inline void reserveVoxels(const size_t set_index, const size_t nVoxels)
306  {
307  ASSERT_(set_index < m_voxel_sets.size());
308  m_voxel_sets[set_index].voxels.reserve(nVoxels);
310  }
311 
312  inline TGridCube& getGridCubeRef(const size_t idx)
313  {
314  ASSERTDEB_(idx < m_grid_cubes.size());
316  return m_grid_cubes[idx];
317  }
318  inline const TGridCube& getGridCube(const size_t idx) const
319  {
320  ASSERTDEB_(idx < m_grid_cubes.size());
321  return m_grid_cubes[idx];
322  }
323 
324  inline TVoxel& getVoxelRef(const size_t set_index, const size_t idx)
325  {
326  ASSERTDEB_(
327  set_index < m_voxel_sets.size() &&
328  idx < m_voxel_sets[set_index].voxels.size());
330  return m_voxel_sets[set_index].voxels[idx];
331  }
332  inline const TVoxel& getVoxel(
333  const size_t set_index, const size_t idx) const
334  {
335  ASSERTDEB_(
336  set_index < m_voxel_sets.size() &&
337  idx < m_voxel_sets[set_index].voxels.size());
339  return m_voxel_sets[set_index].voxels[idx];
340  }
341 
342  inline void push_back_GridCube(const TGridCube& c)
343  {
345  m_grid_cubes.push_back(c);
346  }
347  inline void push_back_Voxel(const size_t set_index, const TVoxel& v)
348  {
349  ASSERTDEB_(set_index < m_voxel_sets.size());
351  m_voxel_sets[set_index].voxels.push_back(v);
352  }
353 
354  void sort_voxels_by_z();
355 
356  void getBoundingBox(
358  mrpt::math::TPoint3D& bb_max) const override;
359 
360  /** Sets the contents of the object from a mrpt::maps::COctoMap object.
361  * \tparam Typically, an mrpt::maps::COctoMap object
362  *
363  * \note Declared as a template because in the library [mrpt-opengl] we
364  * don't have access to the library [mrpt-maps].
365  */
366  template <class OCTOMAP>
367  void setFromOctoMap(OCTOMAP& m)
368  {
369  m.getAsOctoMapVoxels(*this);
370  }
371 
372  /** Constructor */
373  COctoMapVoxels();
374  /** Private, virtual destructor: only can be deleted from smart pointers. */
375  ~COctoMapVoxels() override = default;
376 };
377 
378 } // namespace mrpt::opengl
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)
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
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 freeOpenGLResources() override
Free opengl buffers.
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.
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
TVoxel & getVoxelRef(const size_t set_index, const size_t idx)
void onUpdateBuffers_Wireframe() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY.
mrpt::math::TPoint3Df min
opposite corners of the cube
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)
Transparency goes from opaque (occupied voxel) to transparent (free voxel).
Renderizable generic renderer for objects using the triangles shader.
void clear()
Clears everything.
void freeOpenGLResources() override
Free opengl buffers.
void resizeVoxels(const size_t set_index, const size_t nVoxels)
std::vector< shader_id_t > shader_list_t
A list of shader IDs.
Definition: Shader.h:26
TGridCube(const mrpt::math::TPoint3Df &min_, const mrpt::math::TPoint3Df &max_)
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
void push_back_GridCube(const TGridCube &c)
static constexpr shader_id_t WIREFRAME
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 setGridLinesColor(const mrpt::img::TColor &color)
virtual shader_list_t requiredShaders() const override
Returns the ID of the OpenGL shader program required to render this class.
const TVoxel & getVoxel(const size_t set_index, const size_t idx) const
void onUpdateBuffers_Triangles() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Renderizable generic renderer for objects using the points shader.
const mrpt::img::TColor & getGridLinesColor() const
The info of each grid block.
static constexpr shader_id_t TRIANGLES
void push_back_Voxel(const size_t set_index, const TVoxel &v)
void onUpdateBuffers_Points() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
The info of each of the voxels.
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:190
void resizeVoxelSets(const size_t nVoxelSets)
~COctoMapVoxels() override=default
Private, virtual destructor: only can be deleted from smart pointers.
Renderizable generic renderer for objects using the wireframe shader.
visualization_mode_t getVisualizationMode() const
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
const auto bb_max
void showGridLines(bool show)
Shows/hides the grid lines.
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void setVisualizationMode(visualization_mode_t mode)
Select the visualization mode.
const auto bb_min
std::vector< TGridCube > m_grid_cubes
A RGB color - 8bit.
Definition: TColor.h:25
TVoxel(const mrpt::math::TPoint3Df &coords_, const double side_length_, mrpt::img::TColor color_)
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
void freeOpenGLResources() override
Free opengl buffers.
void resizeGridCubes(const size_t nCubes)
bool isCubeTransparencyEnabled() const
void freeOpenGLResources() override
Free opengl buffers.
static constexpr shader_id_t POINTS
void setGridLinesWidth(float w)
Sets the width of grid lines.



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020