MRPT  2.0.3
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
mrpt::opengl::COctoMapVoxels::showGridLines
void showGridLines(bool show)
Shows/hides the grid lines.
Definition: COctoMapVoxels.h:211
mrpt::opengl::COctoMapVoxels::isCubeTransparencyEnabled
bool isCubeTransparencyEnabled() const
Definition: COctoMapVoxels.h:205
mrpt::opengl::COctoMapVoxels::render
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
Definition: COctoMapVoxels.cpp:42
mrpt::opengl::COctoMapVoxels::areVoxelsVisible
bool areVoxelsVisible(unsigned int voxel_set) const
Definition: COctoMapVoxels.h:225
mrpt::opengl::COctoMapVoxels::m_bb_min
mrpt::math::TPoint3D m_bb_min
Cached bounding boxes.
Definition: COctoMapVoxels.h:142
mrpt::opengl::COctoMapVoxels::enableLights
void enableLights(bool enable)
Can be used to enable/disable the effects of lighting in this object.
Definition: COctoMapVoxels.h:192
mrpt::opengl::COctoMapVoxels::getGridLinesColor
const mrpt::img::TColor & getGridLinesColor() const
Definition: COctoMapVoxels.h:263
mrpt::opengl::COctoMapVoxels::TGridCube::min
mrpt::math::TPoint3Df min
opposite corners of the cube
Definition: COctoMapVoxels.h:118
mrpt::opengl::COctoMapVoxels::COLOR_FROM_OCCUPANCY
@ COLOR_FROM_OCCUPANCY
Color goes from black (occupied voxel) to the chosen color (free voxel)
Definition: COctoMapVoxels.h:85
mrpt::opengl::predefined_voxel_sets_t
predefined_voxel_sets_t
Definition: COctoMapVoxels.h:18
mrpt::opengl::COctoMapVoxels::TRANSPARENCY_FROM_OCCUPANCY
@ TRANSPARENCY_FROM_OCCUPANCY
Transparency goes from opaque (occupied voxel) to transparent (free voxel).
Definition: COctoMapVoxels.h:88
mrpt::opengl::COctoMapVoxels::m_bb_max
mrpt::math::TPoint3D m_bb_max
Definition: COctoMapVoxels.h:142
mrpt::opengl::COctoMapVoxels::m_grid_width
float m_grid_width
Definition: COctoMapVoxels.h:149
mrpt::opengl::CRenderizable::notifyChange
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
Definition: CRenderizable.h:315
mrpt::opengl::COctoMapVoxels::m_show_grids
bool m_show_grids
Definition: COctoMapVoxels.h:148
mrpt::math::TPoint3D_< float >
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:152
mrpt::opengl::COctoMapVoxels::requiredShaders
virtual shader_list_t requiredShaders() const override
Returns the ID of the OpenGL shader program required to render this class.
Definition: COctoMapVoxels.h:159
mrpt::opengl::COctoMapVoxels::TVoxel::side_length
double side_length
Definition: COctoMapVoxels.h:102
mrpt::opengl::COctoMapVoxels::TVoxel::coords
mrpt::math::TPoint3Df coords
Definition: COctoMapVoxels.h:101
mrpt::opengl::COctoMapVoxels::TGridCube
The info of each grid block.
Definition: COctoMapVoxels.h:115
mrpt::opengl::COctoMapVoxels::m_showVoxelsAsPoints
bool m_showVoxelsAsPoints
Definition: COctoMapVoxels.h:146
mrpt::opengl::CRenderizableShaderWireFrame
Renderizable generic renderer for objects using the wireframe shader.
Definition: CRenderizableShaderWireFrame.h:24
mrpt::opengl::COctoMapVoxels::resizeVoxelSets
void resizeVoxelSets(const size_t nVoxelSets)
Definition: COctoMapVoxels.h:289
mrpt::opengl::COctoMapVoxels::getVoxel
const TVoxel & getVoxel(const size_t set_index, const size_t idx) const
Definition: COctoMapVoxels.h:332
mrpt::opengl::COctoMapVoxels::renderUpdateBuffers
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers,...
Definition: COctoMapVoxels.cpp:57
mrpt::opengl::COctoMapVoxels::TInfoPerVoxelSet::visible
bool visible
Definition: COctoMapVoxels.h:131
mrpt::opengl::COctoMapVoxels::~COctoMapVoxels
~COctoMapVoxels() override=default
Private, virtual destructor: only can be deleted from smart pointers.
mrpt::opengl::COctoMapVoxels::TVoxel::TVoxel
TVoxel(const mrpt::math::TPoint3Df &coords_, const double side_length_, mrpt::img::TColor color_)
Definition: COctoMapVoxels.h:106
mrpt::opengl::COctoMapVoxels::getGridCubeCount
size_t getGridCubeCount() const
Returns the total count of grid cubes.
Definition: COctoMapVoxels.h:269
mrpt::opengl::COctoMapVoxels::areVoxelsShownAsPoints
bool areVoxelsShownAsPoints() const
Definition: COctoMapVoxels.h:238
mrpt::opengl::COctoMapVoxels::getVoxelRef
TVoxel & getVoxelRef(const size_t set_index, const size_t idx)
Definition: COctoMapVoxels.h:324
ASSERT_
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
mrpt::opengl::CRenderizableShaderTriangles::freeOpenGLResources
void freeOpenGLResources() override
Free opengl buffers.
Definition: CRenderizableShaderTriangles.h:45
mrpt::opengl::COctoMapVoxels::m_enable_lighting
bool m_enable_lighting
Definition: COctoMapVoxels.h:144
mrpt::opengl::CRenderizableShaderWireFrame::freeOpenGLResources
void freeOpenGLResources() override
Free opengl buffers.
Definition: CRenderizableShaderWireFrame.h:57
mrpt::opengl::COctoMapVoxels::enableCubeTransparency
void enableCubeTransparency(bool enable)
By default, the alpha (transparency) component of voxel cubes is taken into account,...
Definition: COctoMapVoxels.h:200
mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Wireframe
void onUpdateBuffers_Wireframe() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Definition: COctoMapVoxels.cpp:103
mrpt::opengl::COctoMapVoxels::reserveVoxels
void reserveVoxels(const size_t set_index, const size_t nVoxels)
Definition: COctoMapVoxels.h:305
mrpt::opengl::COctoMapVoxels::TInfoPerVoxelSet::voxels
std::vector< TVoxel > voxels
Definition: COctoMapVoxels.h:132
CRenderizableShaderTriangles.h
mrpt::opengl::COctoMapVoxels::TVoxel::TVoxel
TVoxel()=default
mrpt::opengl::COctoMapVoxels::setFromOctoMap
void setFromOctoMap(OCTOMAP &m)
Sets the contents of the object from a mrpt::maps::COctoMap object.
Definition: COctoMapVoxels.h:367
mrpt::opengl::COctoMapVoxels::clear
void clear()
Clears everything.
Definition: COctoMapVoxels.cpp:27
mrpt::opengl::COctoMapVoxels::getVoxelAsPointsSize
float getVoxelAsPointsSize() const
Definition: COctoMapVoxels.h:245
bb_max
const auto bb_max
Definition: CPose3DPDFGrid_unittest.cpp:25
mrpt::opengl::COctoMapVoxels::push_back_GridCube
void push_back_GridCube(const TGridCube &c)
Definition: COctoMapVoxels.h:342
mrpt::opengl::DefaultShaderID::WIREFRAME
static constexpr shader_id_t WIREFRAME
Definition: DefaultShaders.h:25
mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Points
void onUpdateBuffers_Points() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Definition: COctoMapVoxels.cpp:191
bb_min
const auto bb_min
Definition: CPose3DPDFGrid_unittest.cpp:23
mrpt::opengl::COctoMapVoxels::setGridLinesWidth
void setGridLinesWidth(float w)
Sets the width of grid lines.
Definition: COctoMapVoxels.h:251
mrpt::opengl::COctoMapVoxels::visualization_mode_t
visualization_mode_t
The different coloring schemes, which modulate the generic mrpt::opengl::CRenderizable object color.
Definition: COctoMapVoxels.h:78
mrpt::opengl::DefaultShaderID::TRIANGLES
static constexpr shader_id_t TRIANGLES
Definition: DefaultShaders.h:27
mrpt::opengl::COctoMapVoxels::sort_voxels_by_z
void sort_voxels_by_z()
Definition: COctoMapVoxels.cpp:321
mrpt::opengl::COctoMapVoxels::TGridCube::max
mrpt::math::TPoint3Df max
Definition: COctoMapVoxels.h:118
mrpt::opengl::COctoMapVoxels::setBoundingBox
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)
Definition: COctoMapVoxels.cpp:35
mrpt::opengl::COctoMapVoxels::COctoMapVoxels
COctoMapVoxels()
Constructor.
Definition: COctoMapVoxels.cpp:25
CRenderizableShaderWireFrame.h
mrpt::opengl::COctoMapVoxels::setVoxelAsPointsSize
void setVoxelAsPointsSize(float pointSize)
Only used when showVoxelsAsPoints() is enabled.
Definition: COctoMapVoxels.h:240
mrpt::opengl::COctoMapVoxels::TGridCube::TGridCube
TGridCube(const mrpt::math::TPoint3Df &min_, const mrpt::math::TPoint3Df &max_)
Definition: COctoMapVoxels.h:121
mrpt::opengl::COctoMapVoxels::getBoundingBox
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...
Definition: COctoMapVoxels.cpp:304
mrpt::opengl::COctoMapVoxels::showVoxels
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,...
Definition: COctoMapVoxels.h:219
mrpt::img::TColor
A RGB color - 8bit.
Definition: TColor.h:25
mrpt::opengl::COctoMapVoxels::setGridLinesColor
void setGridLinesColor(const mrpt::img::TColor &color)
Definition: COctoMapVoxels.h:258
mrpt::opengl::COctoMapVoxels::areLightsEnabled
bool areLightsEnabled() const
Definition: COctoMapVoxels.h:197
mrpt::opengl::COctoMapVoxels::COLOR_FROM_HEIGHT
@ COLOR_FROM_HEIGHT
Color goes from black (at the bottom) to the chosen color (at the top)
Definition: COctoMapVoxels.h:82
mrpt::opengl::COctoMapVoxels::MIXED
@ MIXED
Combination of COLOR_FROM_HEIGHT and TRANSPARENCY_FROM_OCCUPANCY.
Definition: COctoMapVoxels.h:93
mrpt::opengl::VOXEL_SET_OCCUPIED
@ VOXEL_SET_OCCUPIED
Definition: COctoMapVoxels.h:20
mrpt::opengl::COctoMapVoxels::TVoxel::color
mrpt::img::TColor color
Definition: COctoMapVoxels.h:103
mrpt::opengl::COctoMapVoxels::TInfoPerVoxelSet
Definition: COctoMapVoxels.h:129
mrpt::opengl::VOXEL_SET_FREESPACE
@ VOXEL_SET_FREESPACE
Definition: COctoMapVoxels.h:21
mrpt::opengl::COctoMapVoxels::reserveGridCubes
void reserveGridCubes(const size_t nCubes)
Definition: COctoMapVoxels.h:301
mrpt::opengl::COctoMapVoxels::getGridCube
const TGridCube & getGridCube(const size_t idx) const
Definition: COctoMapVoxels.h:318
mrpt::opengl::COctoMapVoxels::m_visual_mode
visualization_mode_t m_visual_mode
Definition: COctoMapVoxels.h:151
mrpt::opengl::CRenderizableShaderPoints::freeOpenGLResources
void freeOpenGLResources() override
Free opengl buffers.
Definition: CRenderizableShaderPoints.h:86
mrpt::opengl::COctoMapVoxels::getVoxelCount
size_t getVoxelCount(const size_t set_index) const
Returns the total count of voxels in one voxel set.
Definition: COctoMapVoxels.h:273
mrpt::opengl::COctoMapVoxels
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
Definition: COctoMapVoxels.h:69
mrpt::opengl::COctoMapVoxels::areGridLinesVisible
bool areGridLinesVisible() const
Definition: COctoMapVoxels.h:216
mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Triangles
void onUpdateBuffers_Triangles() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Definition: COctoMapVoxels.cpp:135
mrpt::opengl::COctoMapVoxels::getGridCubeRef
TGridCube & getGridCubeRef(const size_t idx)
Definition: COctoMapVoxels.h:312
mrpt::opengl::COctoMapVoxels::resizeGridCubes
void resizeGridCubes(const size_t nCubes)
Definition: COctoMapVoxels.h:284
mrpt::opengl::COctoMapVoxels::m_grid_cubes
std::vector< TGridCube > m_grid_cubes
Definition: COctoMapVoxels.h:139
mrpt::opengl::COctoMapVoxels::setVisualizationMode
void setVisualizationMode(visualization_mode_t mode)
Select the visualization mode.
Definition: COctoMapVoxels.h:181
TPoint3D.h
mrpt::opengl::COctoMapVoxels::push_back_Voxel
void push_back_Voxel(const size_t set_index, const TVoxel &v)
Definition: COctoMapVoxels.h:347
mrpt::opengl::COctoMapVoxels::m_showVoxelsAsPointsSize
float m_showVoxelsAsPointsSize
Definition: COctoMapVoxels.h:147
mrpt::opengl::COctoMapVoxels::getGridLinesWidth
float getGridLinesWidth() const
Gets the width of grid lines.
Definition: COctoMapVoxels.h:257
CRenderizableShaderPoints.h
mrpt::opengl::COctoMapVoxels::resizeVoxels
void resizeVoxels(const size_t set_index, const size_t nVoxels)
Definition: COctoMapVoxels.h:294
mrpt::opengl::COctoMapVoxels::getVoxelSetCount
size_t getVoxelSetCount() const
Returns the number of voxel sets.
Definition: COctoMapVoxels.h:271
mrpt::opengl::COctoMapVoxels::m_enable_cube_transparency
bool m_enable_cube_transparency
Definition: COctoMapVoxels.h:145
mrpt::opengl::CRenderizableShaderPoints
Renderizable generic renderer for objects using the points shader.
Definition: CRenderizableShaderPoints.h:38
mrpt::opengl::shader_list_t
std::vector< shader_id_t > shader_list_t
A list of shader IDs.
Definition: Shader.h:26
ASSERTDEB_
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: exceptions.h:190
mrpt::opengl::CRenderizableShaderTriangles
Renderizable generic renderer for objects using the triangles shader.
Definition: CRenderizableShaderTriangles.h:25
mrpt::opengl::COctoMapVoxels::showVoxelsAsPoints
void showVoxelsAsPoints(const bool enable)
For quick renders: render voxels as points instead of cubes.
Definition: COctoMapVoxels.h:233
mrpt::opengl::COctoMapVoxels::m_voxel_sets
std::deque< TInfoPerVoxelSet > m_voxel_sets
Definition: COctoMapVoxels.h:138
mrpt::opengl::COctoMapVoxels::freeOpenGLResources
void freeOpenGLResources() override
Free opengl buffers.
Definition: COctoMapVoxels.h:168
mrpt::opengl::COctoMapVoxels::FIXED
@ FIXED
All cubes are of identical color.
Definition: COctoMapVoxels.h:95
mrpt::opengl
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
mrpt::opengl::DefaultShaderID::POINTS
static constexpr shader_id_t POINTS
Definition: DefaultShaders.h:24
mrpt::opengl::COctoMapVoxels::m_grid_color
mrpt::img::TColor m_grid_color
Definition: COctoMapVoxels.h:150
mrpt::opengl::COctoMapVoxels::TRANS_AND_COLOR_FROM_OCCUPANCY
@ TRANS_AND_COLOR_FROM_OCCUPANCY
Color goes from black (occupaid voxel) to the chosen color (free voxel) and they are transparent.
Definition: COctoMapVoxels.h:91
mrpt::opengl::COctoMapVoxels::TGridCube::TGridCube
TGridCube()=default
mrpt::opengl::COctoMapVoxels::TVoxel
The info of each of the voxels.
Definition: COctoMapVoxels.h:99
mrpt::opengl::COctoMapVoxels::TInfoPerVoxelSet::TInfoPerVoxelSet
TInfoPerVoxelSet()=default
mrpt::opengl::COctoMapVoxels::getVisualizationMode
visualization_mode_t getVisualizationMode() const
Definition: COctoMapVoxels.h:186



Page generated by Doxygen 1.8.17 for MRPT 2.0.3 at Fri May 15 23:51:15 UTC 2020