MRPT  1.9.9
CColouredOctoMap.cpp
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 
10 #include "maps-precomp.h" // Precomp header
11 
12 #include <octomap/octomap.h>
13 #include <octomap/ColorOcTree.h>
14 
16 #include <mrpt/maps/CPointsMap.h>
19 
23 
24 #include <mrpt/system/filesystem.h>
25 #include <sstream>
27 
28 #include "COctoMapBase_impl.h"
29 
30 // Explicit instantiation:
31 template class mrpt::maps::COctoMapBase<octomap::ColorOcTree,
32  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 
44 // =========== Begin of Map definition ============
46  "CColouredOctoMap,colourOctoMap,colorOctoMap", mrpt::maps::CColouredOctoMap)
47 
49 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(
51  const std::string& sectionNamePrefix)
52 {
53  // [<sectionNamePrefix>+"_creationOpts"]
54  const std::string sSectCreation =
55  sectionNamePrefix + string("_creationOpts");
56  MRPT_LOAD_CONFIG_VAR(resolution, double, source, sSectCreation);
57 
58  insertionOpts.loadFromConfigFile(
59  source, sectionNamePrefix + string("_insertOpts"));
60  likelihoodOpts.loadFromConfigFile(
61  source, sectionNamePrefix + string("_likelihoodOpts"));
62 }
63 
64 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(
65  std::ostream& out) const
66 {
67  LOADABLEOPTS_DUMP_VAR(resolution, double);
68 
69  this->insertionOpts.dumpToTextStream(out);
70  this->likelihoodOpts.dumpToTextStream(out);
71 }
72 
73 mrpt::maps::CMetricMap* CColouredOctoMap::internal_CreateFromMapDefinition(
75 {
77  *dynamic_cast<const CColouredOctoMap::TMapDefinition*>(&_def);
79  obj->insertionOptions = def.insertionOpts;
80  obj->likelihoodOptions = def.likelihoodOpts;
81  return obj;
82 }
83 // =========== End of Map definition Block =========
84 
86 
87 CColouredOctoMap::CColouredOctoMap(const double resolution) :
88  COctoMapBase<octomap::ColorOcTree, octomap::ColorOcTreeNode>(resolution),
89  m_colour_method(INTEGRATE)
90 {
91 }
92 
93 CColouredOctoMap::~CColouredOctoMap() {}
94 uint8_t CColouredOctoMap::serializeGetVersion() const { return 3; }
95 void CColouredOctoMap::serializeTo(mrpt::serialization::CArchive& out) const
96 {
97  this->likelihoodOptions.writeToStream(out);
98  this->renderingOptions.writeToStream(out); // Added in v1
99  out << genericMapParams; // v2
100 
101  // v2->v3: remove CMemoryChunk
102  std::stringstream ss;
103  m_impl->m_octomap.writeBinaryConst(ss);
104  const std::string& buf = ss.str();
105  out << buf;
106 }
107 
108 void CColouredOctoMap::serializeFrom(
110 {
111  switch (version)
112  {
113  case 0:
114  case 1:
115  case 2:
116  {
118  "Deserialization of old versions of this class was "
119  "discontinued in MRPT 1.9.9 [no CMemoryChunk]");
120  }
121  break;
122  case 3:
123  {
124  this->likelihoodOptions.readFromStream(in);
125  if (version >= 1) this->renderingOptions.readFromStream(in);
126  if (version >= 2) in >> genericMapParams;
127 
128  this->clear();
129 
130  std::string buf;
131  in >> buf;
132 
133  if (!buf.empty())
134  {
135  std::stringstream ss;
136  ss.str(buf);
137  ss.seekg(0);
138  m_impl->m_octomap.readBinary(ss);
139  }
140  }
141  break;
142  default:
144  };
145 }
146 
147 /*---------------------------------------------------------------
148  insertObservation
149  ---------------------------------------------------------------*/
150 bool CColouredOctoMap::internal_insertObservation(
151  const mrpt::obs::CObservation* obs, const CPose3D* robotPose)
152 {
153  octomap::point3d sensorPt;
154  octomap::Pointcloud scan;
155 
156  CPose3D robotPose3D;
157  if (robotPose) // Default values are (0,0,0)
158  robotPose3D = (*robotPose);
159 
161  {
162  /********************************************************************
163  OBSERVATION TYPE: CObservation2DRangeScan
164  ********************************************************************/
165  const CObservation2DRangeScan* o =
166  static_cast<const CObservation2DRangeScan*>(obs);
167 
168  // Build a points-map representation of the points from the scan
169  // (coordinates are wrt the robot base)
170 
171  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
172  CPose3D sensorPose(UNINITIALIZED_POSE);
173  sensorPose.composeFrom(robotPose3D, o->sensorPose);
174  sensorPt =
175  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
176 
177  const CPointsMap* scanPts =
179  const size_t nPts = scanPts->size();
180 
181  // Transform 3D point cloud:
182  scan.reserve(nPts);
183 
185  for (size_t i = 0; i < nPts; i++)
186  {
187  // Load the next point:
188  scanPts->getPointFast(i, pt.x, pt.y, pt.z);
189 
190  // Translation:
191  double gx, gy, gz;
192  robotPose3D.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
193 
194  // Add to this map:
195  scan.push_back(gx, gy, gz);
196  }
197 
198  // Insert rays:
199  m_impl->m_octomap.insertPointCloud(
200  scan, sensorPt, insertionOptions.maxrange,
201  insertionOptions.pruning);
202  return true;
203  }
204  else if (IS_CLASS(obs, CObservation3DRangeScan))
205  {
206  /********************************************************************
207  OBSERVATION TYPE: CObservation3DRangeScan
208  ********************************************************************/
209  const CObservation3DRangeScan* o =
210  static_cast<const CObservation3DRangeScan*>(obs);
211 
212  o->load(); // Just to make sure the points are loaded from an external
213  // source, if that's the case...
214 
215  // Project 3D points & color:
217  mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
218  T3DPointsProjectionParams proj_params;
219  proj_params.PROJ3D_USE_LUT = true;
220  proj_params.robotPoseInTheWorld = robotPose;
221  const_cast<CObservation3DRangeScan*>(o)
222  ->project3DPointsFromDepthImageInto(*pts, proj_params);
223 
224  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
225  CPose3D sensorPose(UNINITIALIZED_POSE);
226  sensorPose.composeFrom(robotPose3D, o->sensorPose);
227  sensorPt =
228  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
229 
230  const size_t sizeRangeScan = pts->size();
231  scan.reserve(sizeRangeScan);
232 
233  for (size_t i = 0; i < sizeRangeScan; i++)
234  {
236  pts->getPoint(i);
237 
238  // Add to this map:
239  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
240  scan.push_back(pt.x, pt.y, pt.z);
241  }
242 
243  // Insert rays:
244  octomap::KeySet free_cells, occupied_cells;
245  m_impl->m_octomap
246  .computeUpdate(
247  scan, sensorPt, free_cells, occupied_cells,
248  insertionOptions.maxrange);
249 
250  // insert data into tree -----------------------
251  for (octomap::KeySet::iterator it = free_cells.begin();
252  it != free_cells.end(); ++it)
253  {
254  m_impl->m_octomap.updateNode(*it, false, false);
255  }
256  for (octomap::KeySet::iterator it = occupied_cells.begin();
257  it != occupied_cells.end(); ++it)
258  {
259  m_impl->m_octomap.updateNode(*it, true, false);
260  }
261 
262  // Update color -----------------------
263  const float colF2B = 255.0f;
264  for (size_t i = 0; i < sizeRangeScan; i++)
265  {
267  pts->getPoint(i);
268 
269  // Add to this map:
270  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
271  this->updateVoxelColour(
272  pt.x, pt.y, pt.z, uint8_t(pt.R * colF2B),
273  uint8_t(pt.G * colF2B), uint8_t(pt.B * colF2B));
274  }
275 
276  // TODO: does pruning make sense if we used "lazy_eval"?
277  if (insertionOptions.pruning)
278  m_impl->m_octomap.prune();
279 
280  return true;
281  }
282 
283  return false;
284 }
285 
286 /** Get the RGB colour of a point
287 * \return false if the point is not mapped, in which case the returned colour is
288 * undefined. */
289 bool CColouredOctoMap::getPointColour(
290  const float x, const float y, const float z, uint8_t& r, uint8_t& g,
291  uint8_t& b) const
292 {
293  octomap::OcTreeKey key;
294  if (m_impl->m_octomap
295  .coordToKeyChecked(octomap::point3d(x, y, z), key))
296  {
297  octomap::ColorOcTreeNode* node =
298  m_impl->m_octomap.search(key, 0 /*depth*/);
299  if (!node) return false;
300 
301  const octomap::ColorOcTreeNode::Color& col = node->getColor();
302  r = col.r;
303  g = col.g;
304  b = col.b;
305  return true;
306  }
307  else
308  return false;
309 }
310 
311 /** Manually update the colour of the voxel at (x,y,z) */
312 void CColouredOctoMap::updateVoxelColour(
313  const double x, const double y, const double z, const uint8_t r,
314  const uint8_t g, const uint8_t b)
315 {
316  switch (m_colour_method)
317  {
318  case INTEGRATE:
319  m_impl->m_octomap
320  .integrateNodeColor(x, y, z, r, g, b);
321  break;
322  case SET:
323  m_impl->m_octomap
324  .setNodeColor(x, y, z, r, g, b);
325  break;
326  case AVERAGE:
327  m_impl->m_octomap
328  .averageNodeColor(x, y, z, r, g, b);
329  break;
330  default:
331  THROW_EXCEPTION("Invalid value found for 'm_colour_method'");
332  }
333 }
334 
335 /** Builds a renderizable representation of the octomap as a
336  * mrpt::opengl::COctoMapVoxels object. */
337 void CColouredOctoMap::getAsOctoMapVoxels(
338  mrpt::opengl::COctoMapVoxels& gl_obj) const
339 {
340  // Go thru all voxels:
341 
342  // OcTreeVolume voxel; // current voxel, possibly transformed
343  octomap::ColorOcTree::tree_iterator it_end =
344  m_impl->m_octomap.end_tree();
345 
346  const unsigned char max_depth = 0; // all
347  const TColorf general_color = gl_obj.getColor();
348  const TColor general_color_u(
349  general_color.R * 255, general_color.G * 255, general_color.B * 255,
350  general_color.A * 255);
351 
352  gl_obj.clear();
353  gl_obj.reserveGridCubes(this->calcNumNodes());
354 
355  gl_obj.resizeVoxelSets(2); // 2 sets of voxels: occupied & free
356 
357  gl_obj.showVoxels(
358  VOXEL_SET_OCCUPIED, renderingOptions.visibleOccupiedVoxels);
359  gl_obj.showVoxels(VOXEL_SET_FREESPACE, renderingOptions.visibleFreeVoxels);
360 
361  const size_t nLeafs = this->getNumLeafNodes();
362  gl_obj.reserveVoxels(VOXEL_SET_OCCUPIED, nLeafs);
363  gl_obj.reserveVoxels(VOXEL_SET_FREESPACE, nLeafs);
364 
365  double xmin, xmax, ymin, ymax, zmin, zmax;
366  this->getMetricMin(xmin, ymin, zmin);
367  this->getMetricMax(xmax, ymax, zmax);
368 
369  for (octomap::ColorOcTree::tree_iterator it =
370  m_impl->m_octomap.begin_tree(max_depth);
371  it != it_end; ++it)
372  {
373  const octomap::point3d vx_center = it.getCoordinate();
374  const double vx_length = it.getSize();
375  const double L = 0.5 * vx_length;
376 
377  if (it.isLeaf())
378  {
379  // voxels for leaf nodes
380  const double occ = it->getOccupancy();
381  if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
382  (occ < 0.5 && renderingOptions.generateFreeVoxels))
383  {
384  mrpt::img::TColor vx_color;
385  octomap::ColorOcTreeNode::Color node_color = it->getColor();
386  vx_color = TColor(node_color.r, node_color.g, node_color.b);
387 
388  const size_t vx_set =
389  (m_impl->m_octomap.isNodeOccupied(*it))
392 
393  gl_obj.push_back_Voxel(
394  vx_set,
396  TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
397  vx_length, vx_color));
398  }
399  }
400  else if (renderingOptions.generateGridLines)
401  {
402  // Not leaf-nodes:
403  const mrpt::math::TPoint3D pt_min(
404  vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
405  const mrpt::math::TPoint3D pt_max(
406  vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
407  gl_obj.push_back_GridCube(
408  COctoMapVoxels::TGridCube(pt_min, pt_max));
409  }
410  } // end for each voxel
411 
412  // if we use transparency, sort cubes by "Z" as an approximation to
413  // far-to-near render ordering:
414  if (gl_obj.isCubeTransparencyEnabled()) gl_obj.sort_voxels_by_z();
415 
416  // Set bounding box:
417  {
418  mrpt::math::TPoint3D bbmin, bbmax;
419  this->getMetricMin(bbmin.x, bbmin.y, bbmin.z);
420  this->getMetricMax(bbmax.x, bbmax.y, bbmax.z);
421  gl_obj.setBoundingBox(bbmin, bbmax);
422  }
423 }
424 
425 void CColouredOctoMap::insertRay(
426  const float end_x, const float end_y, const float end_z,
427  const float sensor_x, const float sensor_y, const float sensor_z)
428 {
429  m_impl->m_octomap
430  .insertRay(
431  octomap::point3d(sensor_x, sensor_y, sensor_z),
432  octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange,
433  insertionOptions.pruning);
434 }
435 void CColouredOctoMap::updateVoxel(
436  const double x, const double y, const double z, bool occupied)
437 {
438  m_impl->m_octomap.updateNode(x, y, z, occupied);
439 }
440 bool CColouredOctoMap::isPointWithinOctoMap(
441  const float x, const float y, const float z) const
442 {
443  octomap::OcTreeKey key;
444  return m_impl->m_octomap
445  .coordToKeyChecked(octomap::point3d(x, y, z), key);
446 }
447 
448 double CColouredOctoMap::getResolution() const
449 {
450  return m_impl->m_octomap.getResolution();
451 }
452 unsigned int CColouredOctoMap::getTreeDepth() const
453 {
454  return m_impl->m_octomap.getTreeDepth();
455 }
457 {
458  return m_impl->m_octomap.size();
459 }
460 size_t CColouredOctoMap::memoryUsage() const
461 {
462  return m_impl->m_octomap.memoryUsage();
463 }
464 size_t CColouredOctoMap::memoryUsageNode() const
465 {
466  return m_impl->m_octomap.memoryUsageNode();
467 }
468 size_t CColouredOctoMap::memoryFullGrid() const
469 {
470  return m_impl->m_octomap.memoryFullGrid();
471 }
472 double CColouredOctoMap::volume()
473 {
474  return m_impl->m_octomap.volume();
475 }
476 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z)
477 {
478  return m_impl->m_octomap.getMetricSize(x, y, z);
479 }
480 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z) const
481 {
482  return m_impl->m_octomap.getMetricSize(x, y, z);
483 }
484 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z)
485 {
486  return m_impl->m_octomap.getMetricMin(x, y, z);
487 }
488 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z) const
489 {
490  return m_impl->m_octomap.getMetricMin(x, y, z);
491 }
492 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z)
493 {
494  return m_impl->m_octomap.getMetricMax(x, y, z);
495 }
496 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z) const
497 {
498  return m_impl->m_octomap.getMetricMax(x, y, z);
499 }
500 size_t CColouredOctoMap::calcNumNodes() const
501 {
502  return m_impl->m_octomap.calcNumNodes();
503 }
504 size_t CColouredOctoMap::getNumLeafNodes() const
505 {
506  return m_impl->m_octomap.getNumLeafNodes();
507 }
508 void CColouredOctoMap::setOccupancyThres(double prob)
509 {
510  m_impl->m_octomap.setOccupancyThres(prob);
511 }
512 void CColouredOctoMap::setProbHit(double prob)
513 {
514  m_impl->m_octomap.setProbHit(prob);
515 }
516 void CColouredOctoMap::setProbMiss(double prob)
517 {
518  m_impl->m_octomap.setProbMiss(prob);
519 }
520 void CColouredOctoMap::setClampingThresMin(double thresProb)
521 {
522  m_impl->m_octomap.setClampingThresMin(thresProb);
523 }
524 void CColouredOctoMap::setClampingThresMax(double thresProb)
525 {
526  m_impl->m_octomap.setClampingThresMax(thresProb);
527 }
528 double CColouredOctoMap::getOccupancyThres() const
529 {
530  return m_impl->m_octomap.getOccupancyThres();
531 }
532 float CColouredOctoMap::getOccupancyThresLog() const
533 {
534  return m_impl->m_octomap.getOccupancyThresLog();
535 }
536 double CColouredOctoMap::getProbHit() const
537 {
538  return m_impl->m_octomap.getProbHit();
539 }
540 float CColouredOctoMap::getProbHitLog() const
541 {
542  return m_impl->m_octomap.getProbHitLog();
543 }
544 double CColouredOctoMap::getProbMiss() const
545 {
546  return m_impl->m_octomap.getProbMiss();
547 }
548 float CColouredOctoMap::getProbMissLog() const
549 {
550  return m_impl->m_octomap.getProbMissLog();
551 }
552 double CColouredOctoMap::getClampingThresMin() const
553 {
554  return m_impl->m_octomap.getClampingThresMin();
555 }
556 float CColouredOctoMap::getClampingThresMinLog() const
557 {
558  return m_impl->m_octomap.getClampingThresMinLog();
559 }
560 double CColouredOctoMap::getClampingThresMax() const
561 {
562  return m_impl->m_octomap.getClampingThresMax();
563 }
564 float CColouredOctoMap::getClampingThresMaxLog() const
565 {
566  return m_impl->m_octomap.getClampingThresMaxLog();
567 }
568 void CColouredOctoMap::internal_clear()
569 {
570  m_impl->m_octomap.clear();
571 }
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:140
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...
Scalar * iterator
Definition: eigen_plugins.h:26
void reserveVoxels(const size_t set_index, const size_t nVoxels)
GLdouble GLdouble z
Definition: glext.h:3872
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in 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:4070
unsigned char uint8_t
Definition: rptypes.h:41
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:90
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:46
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:64
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).
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:565
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:6279
This namespace contains representation of robot actions and observations.
GLubyte GLubyte b
Definition: glext.h:6279
double x
X,Y,Z coordinates.
GLsizei const GLchar ** string
Definition: glext.h:4101
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:7918
#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:52
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:54
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
void resizeVoxelSets(const size_t nVoxelSets)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< 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:379
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::rtti::CObject) is of the give...
Definition: CObject.h:102
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:7274
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
GLenum GLint GLint y
Definition: glext.h:3538
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:3923
A RGB color - 8bit.
Definition: TColor.h:20
GLenum GLint x
Definition: glext.h:3538
Lightweight 3D point.
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:408
bool isCubeTransparencyEnabled() const
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:186
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
virtual 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: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020