MRPT  1.9.9
CColouredOctoMap.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, 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 
10 #include "maps-precomp.h" // Precomp header
11 
12 #include <octomap/ColorOcTree.h>
13 #include <octomap/octomap.h>
14 
16 #include <mrpt/maps/CPointsMap.h>
19 
23 
25 #include <mrpt/system/filesystem.h>
26 #include <sstream>
27 
28 #include "COctoMapBase_impl.h"
29 
30 // Explicit instantiation:
31 template class mrpt::maps::COctoMapBase<
32  octomap::ColorOcTree, octomap::ColorOcTreeNode>;
33 
34 using namespace std;
35 using namespace mrpt;
36 using namespace mrpt::maps;
37 using namespace mrpt::obs;
38 using namespace mrpt::poses;
39 using namespace mrpt::img;
40 using namespace mrpt::opengl;
41 using namespace mrpt::math;
42 
43 // =========== Begin of Map definition ============
45  "CColouredOctoMap,colourOctoMap,colorOctoMap", mrpt::maps::CColouredOctoMap)
46 
47 CColouredOctoMap::TMapDefinition::TMapDefinition() = default;
48 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(
50  const std::string& sectionNamePrefix)
51 {
52  // [<sectionNamePrefix>+"_creationOpts"]
53  const std::string sSectCreation =
54  sectionNamePrefix + string("_creationOpts");
55  MRPT_LOAD_CONFIG_VAR(resolution, double, source, sSectCreation);
56 
57  insertionOpts.loadFromConfigFile(
58  source, sectionNamePrefix + string("_insertOpts"));
59  likelihoodOpts.loadFromConfigFile(
60  source, sectionNamePrefix + string("_likelihoodOpts"));
61 }
62 
63 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(
64  std::ostream& out) const
65 {
66  LOADABLEOPTS_DUMP_VAR(resolution, double);
67 
68  this->insertionOpts.dumpToTextStream(out);
69  this->likelihoodOpts.dumpToTextStream(out);
70 }
71 
72 mrpt::maps::CMetricMap* CColouredOctoMap::internal_CreateFromMapDefinition(
74 {
76  *dynamic_cast<const CColouredOctoMap::TMapDefinition*>(&_def);
77  auto* obj = new CColouredOctoMap(def.resolution);
78  obj->insertionOptions = def.insertionOpts;
79  obj->likelihoodOptions = def.likelihoodOpts;
80  return obj;
81 }
82 // =========== End of Map definition Block =========
83 
85 
86 CColouredOctoMap::CColouredOctoMap(const double resolution)
87  : COctoMapBase<octomap::ColorOcTree, octomap::ColorOcTreeNode>(resolution)
88 
89 {
90 }
91 
92 CColouredOctoMap::~CColouredOctoMap() = default;
93 uint8_t CColouredOctoMap::serializeGetVersion() const { return 3; }
94 void CColouredOctoMap::serializeTo(mrpt::serialization::CArchive& out) const
95 {
96  this->likelihoodOptions.writeToStream(out);
97  this->renderingOptions.writeToStream(out); // Added in v1
98  out << genericMapParams; // v2
99 
100  // v2->v3: remove CMemoryChunk
101  std::stringstream ss;
102  m_impl->m_octomap.writeBinaryConst(ss);
103  const std::string& buf = ss.str();
104  out << buf;
105 }
106 
107 void CColouredOctoMap::serializeFrom(
109 {
110  switch (version)
111  {
112  case 0:
113  case 1:
114  case 2:
115  {
117  "Deserialization of old versions of this class was "
118  "discontinued in MRPT 1.9.9 [no CMemoryChunk]");
119  }
120  break;
121  case 3:
122  {
123  this->likelihoodOptions.readFromStream(in);
124  if (version >= 1) this->renderingOptions.readFromStream(in);
125  if (version >= 2) in >> genericMapParams;
126 
127  this->clear();
128 
129  std::string buf;
130  in >> buf;
131 
132  if (!buf.empty())
133  {
134  std::stringstream ss;
135  ss.str(buf);
136  ss.seekg(0);
137  m_impl->m_octomap.readBinary(ss);
138  }
139  }
140  break;
141  default:
143  };
144 }
145 
146 /*---------------------------------------------------------------
147  insertObservation
148  ---------------------------------------------------------------*/
149 bool CColouredOctoMap::internal_insertObservation(
150  const mrpt::obs::CObservation& obs, const CPose3D* robotPose)
151 {
152  octomap::point3d sensorPt;
153  octomap::Pointcloud scan;
154 
155  CPose3D robotPose3D;
156  if (robotPose) // Default values are (0,0,0)
157  robotPose3D = (*robotPose);
158 
160  {
161  /********************************************************************
162  OBSERVATION TYPE: CObservation2DRangeScan
163  ********************************************************************/
164  const auto& o = static_cast<const CObservation2DRangeScan&>(obs);
165 
166  // Build a points-map representation of the points from the scan
167  // (coordinates are wrt the robot base)
168 
169  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
170  CPose3D sensorPose(UNINITIALIZED_POSE);
171  sensorPose.composeFrom(robotPose3D, o.sensorPose);
172  sensorPt =
173  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
174 
175  const auto* scanPts = o.buildAuxPointsMap<mrpt::maps::CPointsMap>();
176  const size_t nPts = scanPts->size();
177 
178  // Transform 3D point cloud:
179  scan.reserve(nPts);
180 
182  for (size_t i = 0; i < nPts; i++)
183  {
184  // Load the next point:
185  scanPts->getPointFast(i, pt.x, pt.y, pt.z);
186 
187  // Translation:
188  double gx, gy, gz;
189  robotPose3D.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
190 
191  // Add to this map:
192  scan.push_back(gx, gy, gz);
193  }
194 
195  // Insert rays:
196  m_impl->m_octomap.insertPointCloud(
197  scan, sensorPt, insertionOptions.maxrange,
198  insertionOptions.pruning);
199  return true;
200  }
201  else if (IS_CLASS(obs, CObservation3DRangeScan))
202  {
203  /********************************************************************
204  OBSERVATION TYPE: CObservation3DRangeScan
205  ********************************************************************/
206  const auto& o = static_cast<const CObservation3DRangeScan&>(obs);
207 
208  o.load(); // Just to make sure the points are loaded from an external
209  // source, if that's the case...
210 
211  // Project 3D points & color:
214  T3DPointsProjectionParams proj_params;
215  proj_params.PROJ3D_USE_LUT = true;
216  proj_params.robotPoseInTheWorld = robotPose;
217  const_cast<CObservation3DRangeScan&>(o)
218  .project3DPointsFromDepthImageInto(*pts, proj_params);
219 
220  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
221  CPose3D sensorPose(UNINITIALIZED_POSE);
222  sensorPose.composeFrom(robotPose3D, o.sensorPose);
223  sensorPt =
224  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
225 
226  const size_t sizeRangeScan = pts->size();
227  scan.reserve(sizeRangeScan);
228 
229  for (size_t i = 0; i < sizeRangeScan; i++)
230  {
232  pts->getPoint(i);
233 
234  // Add to this map:
235  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
236  scan.push_back(pt.x, pt.y, pt.z);
237  }
238 
239  // Insert rays:
240  octomap::KeySet free_cells, occupied_cells;
241  m_impl->m_octomap.computeUpdate(
242  scan, sensorPt, free_cells, occupied_cells,
243  insertionOptions.maxrange);
244 
245  // insert data into tree -----------------------
246  for (const auto& free_cell : free_cells)
247  {
248  m_impl->m_octomap.updateNode(free_cell, false, false);
249  }
250  for (const auto& occupied_cell : occupied_cells)
251  {
252  m_impl->m_octomap.updateNode(occupied_cell, true, false);
253  }
254 
255  // Update color -----------------------
256  const float colF2B = 255.0f;
257  for (size_t i = 0; i < sizeRangeScan; i++)
258  {
260  pts->getPoint(i);
261 
262  // Add to this map:
263  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
264  this->updateVoxelColour(
265  pt.x, pt.y, pt.z, uint8_t(pt.R * colF2B),
266  uint8_t(pt.G * colF2B), uint8_t(pt.B * colF2B));
267  }
268 
269  // TODO: does pruning make sense if we used "lazy_eval"?
270  if (insertionOptions.pruning) m_impl->m_octomap.prune();
271 
272  return true;
273  }
274 
275  return false;
276 }
277 
278 /** Get the RGB colour of a point
279  * \return false if the point is not mapped, in which case the returned colour
280  * is undefined. */
281 bool CColouredOctoMap::getPointColour(
282  const float x, const float y, const float z, uint8_t& r, uint8_t& g,
283  uint8_t& b) const
284 {
285  octomap::OcTreeKey key;
286  if (m_impl->m_octomap.coordToKeyChecked(octomap::point3d(x, y, z), key))
287  {
288  octomap::ColorOcTreeNode* node =
289  m_impl->m_octomap.search(key, 0 /*depth*/);
290  if (!node) return false;
291 
292  const octomap::ColorOcTreeNode::Color& col = node->getColor();
293  r = col.r;
294  g = col.g;
295  b = col.b;
296  return true;
297  }
298  else
299  return false;
300 }
301 
302 /** Manually update the colour of the voxel at (x,y,z) */
303 void CColouredOctoMap::updateVoxelColour(
304  const double x, const double y, const double z, const uint8_t r,
305  const uint8_t g, const uint8_t b)
306 {
307  switch (m_colour_method)
308  {
309  case INTEGRATE:
310  m_impl->m_octomap.integrateNodeColor(x, y, z, r, g, b);
311  break;
312  case SET:
313  m_impl->m_octomap.setNodeColor(x, y, z, r, g, b);
314  break;
315  case AVERAGE:
316  m_impl->m_octomap.averageNodeColor(x, y, z, r, g, b);
317  break;
318  default:
319  THROW_EXCEPTION("Invalid value found for 'm_colour_method'");
320  }
321 }
322 
323 /** Builds a renderizable representation of the octomap as a
324  * mrpt::opengl::COctoMapVoxels object. */
325 void CColouredOctoMap::getAsOctoMapVoxels(
326  mrpt::opengl::COctoMapVoxels& gl_obj) const
327 {
328  // Go thru all voxels:
329 
330  // OcTreeVolume voxel; // current voxel, possibly transformed
331  octomap::ColorOcTree::tree_iterator it_end = m_impl->m_octomap.end_tree();
332 
333  const unsigned char max_depth = 0; // all
334  const TColorf general_color = gl_obj.getColor();
335  const TColor general_color_u(
336  general_color.R * 255, general_color.G * 255, general_color.B * 255,
337  general_color.A * 255);
338 
339  gl_obj.clear();
340  gl_obj.reserveGridCubes(this->calcNumNodes());
341 
342  gl_obj.resizeVoxelSets(2); // 2 sets of voxels: occupied & free
343 
344  gl_obj.showVoxels(
345  VOXEL_SET_OCCUPIED, renderingOptions.visibleOccupiedVoxels);
346  gl_obj.showVoxels(VOXEL_SET_FREESPACE, renderingOptions.visibleFreeVoxels);
347 
348  const size_t nLeafs = this->getNumLeafNodes();
349  gl_obj.reserveVoxels(VOXEL_SET_OCCUPIED, nLeafs);
350  gl_obj.reserveVoxels(VOXEL_SET_FREESPACE, nLeafs);
351 
352  double xmin, xmax, ymin, ymax, zmin, zmax;
353  this->getMetricMin(xmin, ymin, zmin);
354  this->getMetricMax(xmax, ymax, zmax);
355 
356  for (octomap::ColorOcTree::tree_iterator it =
357  m_impl->m_octomap.begin_tree(max_depth);
358  it != it_end; ++it)
359  {
360  const octomap::point3d vx_center = it.getCoordinate();
361  const double vx_length = it.getSize();
362  const double L = 0.5 * vx_length;
363 
364  if (it.isLeaf())
365  {
366  // voxels for leaf nodes
367  const double occ = it->getOccupancy();
368  if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
369  (occ < 0.5 && renderingOptions.generateFreeVoxels))
370  {
371  mrpt::img::TColor vx_color;
372  octomap::ColorOcTreeNode::Color node_color = it->getColor();
373  vx_color = TColor(node_color.r, node_color.g, node_color.b);
374 
375  const size_t vx_set = (m_impl->m_octomap.isNodeOccupied(*it))
378 
379  gl_obj.push_back_Voxel(
380  vx_set,
382  TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
383  vx_length, vx_color));
384  }
385  }
386  else if (renderingOptions.generateGridLines)
387  {
388  // Not leaf-nodes:
389  const mrpt::math::TPoint3D pt_min(
390  vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
391  const mrpt::math::TPoint3D pt_max(
392  vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
393  gl_obj.push_back_GridCube(
394  COctoMapVoxels::TGridCube(pt_min, pt_max));
395  }
396  } // end for each voxel
397 
398  // if we use transparency, sort cubes by "Z" as an approximation to
399  // far-to-near render ordering:
400  if (gl_obj.isCubeTransparencyEnabled()) gl_obj.sort_voxels_by_z();
401 
402  // Set bounding box:
403  {
404  mrpt::math::TPoint3D bbmin, bbmax;
405  this->getMetricMin(bbmin.x, bbmin.y, bbmin.z);
406  this->getMetricMax(bbmax.x, bbmax.y, bbmax.z);
407  gl_obj.setBoundingBox(bbmin, bbmax);
408  }
409 }
410 
411 void CColouredOctoMap::insertRay(
412  const float end_x, const float end_y, const float end_z,
413  const float sensor_x, const float sensor_y, const float sensor_z)
414 {
415  m_impl->m_octomap.insertRay(
416  octomap::point3d(sensor_x, sensor_y, sensor_z),
417  octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange,
418  insertionOptions.pruning);
419 }
420 void CColouredOctoMap::updateVoxel(
421  const double x, const double y, const double z, bool occupied)
422 {
423  m_impl->m_octomap.updateNode(x, y, z, occupied);
424 }
425 bool CColouredOctoMap::isPointWithinOctoMap(
426  const float x, const float y, const float z) const
427 {
428  octomap::OcTreeKey key;
429  return m_impl->m_octomap.coordToKeyChecked(octomap::point3d(x, y, z), key);
430 }
431 
432 double CColouredOctoMap::getResolution() const
433 {
434  return m_impl->m_octomap.getResolution();
435 }
436 unsigned int CColouredOctoMap::getTreeDepth() const
437 {
438  return m_impl->m_octomap.getTreeDepth();
439 }
440 size_t CColouredOctoMap::size() const { return m_impl->m_octomap.size(); }
441 size_t CColouredOctoMap::memoryUsage() const
442 {
443  return m_impl->m_octomap.memoryUsage();
444 }
445 size_t CColouredOctoMap::memoryUsageNode() const
446 {
447  return m_impl->m_octomap.memoryUsageNode();
448 }
449 size_t CColouredOctoMap::memoryFullGrid() const
450 {
451  return m_impl->m_octomap.memoryFullGrid();
452 }
453 double CColouredOctoMap::volume() { return m_impl->m_octomap.volume(); }
454 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z)
455 {
456  return m_impl->m_octomap.getMetricSize(x, y, z);
457 }
458 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z) const
459 {
460  return m_impl->m_octomap.getMetricSize(x, y, z);
461 }
462 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z)
463 {
464  return m_impl->m_octomap.getMetricMin(x, y, z);
465 }
466 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z) const
467 {
468  return m_impl->m_octomap.getMetricMin(x, y, z);
469 }
470 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z)
471 {
472  return m_impl->m_octomap.getMetricMax(x, y, z);
473 }
474 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z) const
475 {
476  return m_impl->m_octomap.getMetricMax(x, y, z);
477 }
478 size_t CColouredOctoMap::calcNumNodes() const
479 {
480  return m_impl->m_octomap.calcNumNodes();
481 }
482 size_t CColouredOctoMap::getNumLeafNodes() const
483 {
484  return m_impl->m_octomap.getNumLeafNodes();
485 }
486 void CColouredOctoMap::setOccupancyThres(double prob)
487 {
488  m_impl->m_octomap.setOccupancyThres(prob);
489 }
490 void CColouredOctoMap::setProbHit(double prob)
491 {
492  m_impl->m_octomap.setProbHit(prob);
493 }
494 void CColouredOctoMap::setProbMiss(double prob)
495 {
496  m_impl->m_octomap.setProbMiss(prob);
497 }
498 void CColouredOctoMap::setClampingThresMin(double thresProb)
499 {
500  m_impl->m_octomap.setClampingThresMin(thresProb);
501 }
502 void CColouredOctoMap::setClampingThresMax(double thresProb)
503 {
504  m_impl->m_octomap.setClampingThresMax(thresProb);
505 }
506 double CColouredOctoMap::getOccupancyThres() const
507 {
508  return m_impl->m_octomap.getOccupancyThres();
509 }
510 float CColouredOctoMap::getOccupancyThresLog() const
511 {
512  return m_impl->m_octomap.getOccupancyThresLog();
513 }
514 double CColouredOctoMap::getProbHit() const
515 {
516  return m_impl->m_octomap.getProbHit();
517 }
518 float CColouredOctoMap::getProbHitLog() const
519 {
520  return m_impl->m_octomap.getProbHitLog();
521 }
522 double CColouredOctoMap::getProbMiss() const
523 {
524  return m_impl->m_octomap.getProbMiss();
525 }
526 float CColouredOctoMap::getProbMissLog() const
527 {
528  return m_impl->m_octomap.getProbMissLog();
529 }
530 double CColouredOctoMap::getClampingThresMin() const
531 {
532  return m_impl->m_octomap.getClampingThresMin();
533 }
534 float CColouredOctoMap::getClampingThresMinLog() const
535 {
536  return m_impl->m_octomap.getClampingThresMinLog();
537 }
538 double CColouredOctoMap::getClampingThresMax() const
539 {
540  return m_impl->m_octomap.getClampingThresMax();
541 }
542 float CColouredOctoMap::getClampingThresMaxLog() const
543 {
544  return m_impl->m_octomap.getClampingThresMaxLog();
545 }
546 void CColouredOctoMap::internal_clear() { m_impl->m_octomap.clear(); }
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.
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
void reserveVoxels(const size_t set_index, const size_t nVoxels)
GLdouble GLdouble z
Definition: glext.h:3879
double x
X,Y,Z coordinates.
Definition: TPoint3D.h:83
static Ptr Create(Args &&... args)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixed< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dse3=nullptr, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
Definition: CPose3D.cpp:368
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: nullptr) Read takeIntoAccountSensorPoseOnRobot
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
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)
void reserveGridCubes(const size_t nCubes)
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
mrpt::maps::CColouredOctoMap::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
STL namespace.
void clear()
Clears everything.
GLsizei GLsizei GLuint * obj
Definition: glext.h:4085
unsigned char uint8_t
Definition: rptypes.h:44
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:97
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:45
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void push_back_GridCube(const TGridCube &c)
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:65
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts
meters)
Lightweight 3D point (float version).
Definition: TPoint3D.h:21
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
Definition: CPose3D.cpp:563
void project3DPointsFromDepthImageInto(mrpt::obs::CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const mrpt::obs::T3DPointsProjectionParams &projectParams, const mrpt::obs::TRangeImageFilterParams &filterParams)
GLubyte g
Definition: glext.h:6372
This namespace contains representation of robot actions and observations.
GLubyte GLubyte b
Definition: glext.h:6372
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
Definition: CObject.h:133
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:143
GLsizei const GLchar ** string
Definition: glext.h:4116
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
The info of each grid block.
void push_back_Voxel(const size_t set_index, const TVoxel &v)
GLclampd zmax
Definition: glext.h:8064
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
The info of each of the voxels.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define MAP_DEFINITION_REGISTER(_CLASSNAME_STRINGS, _CLASSNAME_WITH_NS)
Registers one map class into TMetricMapInitializer factory.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:53
GLdouble GLdouble GLdouble r
Definition: glext.h:3711
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:84
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
void resizeVoxelSets(const size_t nVoxelSets)
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
mrpt::img::TColorf getColor() const
Returns the object color property as a TColorf.
A RGB color - floats in the range [0,1].
Definition: TColor.h:77
GLuint in
Definition: glext.h:7391
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
GLsizei GLsizei GLchar * source
Definition: glext.h:4097
GLenum GLint GLint y
Definition: glext.h:3542
bool PROJ3D_USE_LUT
(Default:true) [Only used when range_is_depth=true] Whether to use a Look-up-table (LUT) to speed up ...
GLsizeiptr size
Definition: glext.h:3934
A RGB color - 8bit.
Definition: TColor.h:20
GLenum GLint x
Definition: glext.h:3542
Lightweight 3D point.
Definition: TPoint3D.h:90
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
double resolution
The finest resolution of the octomap (default: 0.10.
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:422
bool isCubeTransparencyEnabled() const
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:182
void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019