Main MRPT website > C++ reference for MRPT 1.5.7
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-2017, 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 #include <mrpt/utils/pimpl.h>
15 PIMPL_IMPLEMENT(octomap::ColorOcTree);
16 
18 #include <mrpt/maps/CPointsMap.h>
21 
25 
26 #include <mrpt/system/filesystem.h>
29 
30 #include "COctoMapBase_impl.h"
31 
32 // Explicit instantiation:
34 
35 
36 using namespace std;
37 using namespace mrpt;
38 using namespace mrpt::maps;
39 using namespace mrpt::obs;
40 using namespace mrpt::utils;
41 using namespace mrpt::poses;
42 using namespace mrpt::opengl;
43 using namespace mrpt::math;
44 
45 // =========== Begin of Map definition ============
46 MAP_DEFINITION_REGISTER("CColouredOctoMap,colourOctoMap,colorOctoMap", mrpt::maps::CColouredOctoMap)
47 
49  resolution(0.10)
50 {
51 }
52 
53 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(const mrpt::utils::CConfigFileBase &source, const std::string &sectionNamePrefix)
54 {
55  // [<sectionNamePrefix>+"_creationOpts"]
56  const std::string sSectCreation = sectionNamePrefix+string("_creationOpts");
57  MRPT_LOAD_CONFIG_VAR(resolution, double, source,sSectCreation);
58 
59  insertionOpts.loadFromConfigFile(source, sectionNamePrefix+string("_insertOpts") );
60  likelihoodOpts.loadFromConfigFile(source, sectionNamePrefix+string("_likelihoodOpts") );
61 }
62 
63 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(mrpt::utils::CStream &out) const
64 {
65  LOADABLEOPTS_DUMP_VAR(resolution , double);
66 
67  this->insertionOpts.dumpToTextStream(out);
68  this->likelihoodOpts.dumpToTextStream(out);
69 }
70 
71 mrpt::maps::CMetricMap* CColouredOctoMap::internal_CreateFromMapDefinition(const mrpt::maps::TMetricMapInitializer &_def)
72 {
73  const CColouredOctoMap::TMapDefinition &def = *dynamic_cast<const CColouredOctoMap::TMapDefinition*>(&_def);
75  obj->insertionOptions = def.insertionOpts;
76  obj->likelihoodOptions = def.likelihoodOpts;
77  return obj;
78 }
79 // =========== End of Map definition Block =========
80 
81 
83 
84 /*---------------------------------------------------------------
85  Constructor
86  ---------------------------------------------------------------*/
87 CColouredOctoMap::CColouredOctoMap(const double resolution) :
88  m_colour_method(INTEGRATE)
89 {
90  m_octomap.ptr.reset(new octomap::ColorOcTree(resolution));
91 }
92 
93 /*---------------------------------------------------------------
94  Destructor
95  ---------------------------------------------------------------*/
96 CColouredOctoMap::~CColouredOctoMap()
97 {
98 }
99 
100 /*---------------------------------------------------------------
101  writeToStream
102  Implements the writing to a CStream capability of
103  CSerializable objects
104  ---------------------------------------------------------------*/
105 void CColouredOctoMap::writeToStream(mrpt::utils::CStream &out, int *version) const
106 {
107  if (version)
108  *version = 2;
109  else
110  {
111  this->likelihoodOptions.writeToStream(out);
112  this->renderingOptions.writeToStream(out); // Added in v1
113  out << genericMapParams; // v2
114 
115  CMemoryChunk chunk;
116  const string tmpFil = mrpt::system::getTempFileName();
117  const_cast<octomap::ColorOcTree*>(&PIMPL_GET_REF(ColorOcTree,m_octomap))->writeBinary(tmpFil);
118  chunk.loadBufferFromFile(tmpFil);
119  mrpt::system::deleteFile(tmpFil);
120  out << chunk;
121 
122  }
123 }
124 
125 /*---------------------------------------------------------------
126  readFromStream
127  Implements the reading from a CStream capability of
128  CSerializable objects
129  ---------------------------------------------------------------*/
130 void CColouredOctoMap::readFromStream(mrpt::utils::CStream &in, int version)
131 {
132  switch(version)
133  {
134  case 0:
135  case 1:
136  case 2:
137  {
138  this->likelihoodOptions.readFromStream(in);
139  if (version>=1) this->renderingOptions.readFromStream(in);
140  if (version>=2) in >> genericMapParams;
141 
142  this->clear();
143 
144  CMemoryChunk chunk;
145  in >> chunk;
146 
147  if (chunk.getTotalBytesCount())
148  {
149  const string tmpFil = mrpt::system::getTempFileName();
150  if (!chunk.saveBufferToFile( tmpFil ) ) THROW_EXCEPTION("Error saving temporary file");
151  PIMPL_GET_REF(ColorOcTree, m_octomap).readBinary(tmpFil);
152  mrpt::system::deleteFile( tmpFil );
153  }
154 
155  } break;
156  default:
158  };
159 
160 }
161 
162 /*---------------------------------------------------------------
163  insertObservation
164  ---------------------------------------------------------------*/
165 bool CColouredOctoMap::internal_insertObservation(const mrpt::obs::CObservation *obs,const CPose3D *robotPose)
166 {
167  octomap::point3d sensorPt;
168  octomap::Pointcloud scan;
169 
170  CPose3D robotPose3D;
171  if (robotPose) // Default values are (0,0,0)
172  robotPose3D = (*robotPose);
173 
175  {
176  /********************************************************************
177  OBSERVATION TYPE: CObservation2DRangeScan
178  ********************************************************************/
179  const CObservation2DRangeScan *o = static_cast<const CObservation2DRangeScan*>( obs );
180 
181  // Build a points-map representation of the points from the scan (coordinates are wrt the robot base)
182 
183  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
184  CPose3D sensorPose(UNINITIALIZED_POSE);
185  sensorPose.composeFrom(robotPose3D,o->sensorPose);
186  sensorPt = octomap::point3d(sensorPose.x(),sensorPose.y(),sensorPose.z());
187 
188  const CPointsMap *scanPts = o->buildAuxPointsMap<mrpt::maps::CPointsMap>();
189  const size_t nPts = scanPts->size();
190 
191  // Transform 3D point cloud:
192  scan.reserve(nPts);
193 
195  for (size_t i=0;i<nPts;i++)
196  {
197  // Load the next point:
198  scanPts->getPointFast(i,pt.x,pt.y,pt.z);
199 
200  // Translation:
201  double gx,gy,gz;
202  robotPose3D.composePoint(pt.x,pt.y,pt.z, gx,gy,gz);
203 
204  // Add to this map:
205  scan.push_back(gx,gy,gz);
206  }
207 
208  // Insert rays:
209  PIMPL_GET_REF(ColorOcTree, m_octomap).insertPointCloud(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning);
210  return true;
211  }
212  else if ( IS_CLASS(obs,CObservation3DRangeScan) )
213  {
214  /********************************************************************
215  OBSERVATION TYPE: CObservation3DRangeScan
216  ********************************************************************/
217  const CObservation3DRangeScan *o = static_cast<const CObservation3DRangeScan*>( obs );
218 
219  o->load(); // Just to make sure the points are loaded from an external source, if that's the case...
220 
221  // Project 3D points & color:
222  mrpt::opengl::CPointCloudColouredPtr pts = mrpt::opengl::CPointCloudColoured::Create();
223  T3DPointsProjectionParams proj_params;
224  proj_params.PROJ3D_USE_LUT = true;
225  proj_params.robotPoseInTheWorld = robotPose;
226  const_cast<CObservation3DRangeScan*>(o)->project3DPointsFromDepthImageInto(*pts,proj_params);
227 
228  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
229  CPose3D sensorPose(UNINITIALIZED_POSE);
230  sensorPose.composeFrom(robotPose3D,o->sensorPose);
231  sensorPt = octomap::point3d(sensorPose.x(),sensorPose.y(),sensorPose.z());
232 
233  const size_t sizeRangeScan = pts->size();
234  scan.reserve(sizeRangeScan);
235 
236  for (size_t i=0;i<sizeRangeScan;i++)
237  {
238  const mrpt::opengl::CPointCloudColoured::TPointColour & pt = pts->getPoint(i);
239 
240  // Add to this map:
241  if (pt.x!=0 || pt.y!=0 || pt.z!=0)
242  scan.push_back(pt.x,pt.y,pt.z);
243  }
244 
245  // Insert rays:
246  octomap::KeySet free_cells, occupied_cells;
247  PIMPL_GET_REF(ColorOcTree, m_octomap).computeUpdate(scan, sensorPt, free_cells, occupied_cells, insertionOptions.maxrange);
248 
249  // insert data into tree -----------------------
250  for (octomap::KeySet::iterator it = free_cells.begin(); it != free_cells.end(); ++it) {
251  PIMPL_GET_REF(ColorOcTree, m_octomap).updateNode(*it, false, false);
252  }
253  for (octomap::KeySet::iterator it = occupied_cells.begin(); it != occupied_cells.end(); ++it) {
254  PIMPL_GET_REF(ColorOcTree, m_octomap).updateNode(*it, true, false);
255  }
256 
257  // Update color -----------------------
258  const float colF2B = 255.0f;
259  for (size_t i=0;i<sizeRangeScan;i++)
260  {
261  const mrpt::opengl::CPointCloudColoured::TPointColour & pt = pts->getPoint(i);
262 
263  // Add to this map:
264  if (pt.x!=0 || pt.y!=0 || pt.z!=0)
265  this->updateVoxelColour(pt.x,pt.y,pt.z, uint8_t(pt.R*colF2B),uint8_t(pt.G*colF2B),uint8_t(pt.B*colF2B) );
266  }
267 
268  // TODO: does pruning make sense if we used "lazy_eval"?
269  if (insertionOptions.pruning) PIMPL_GET_REF(ColorOcTree, m_octomap).prune();
270 
271  return true;
272  }
273 
274  return false;
275 }
276 
277 /** Get the RGB colour of a point
278 * \return false if the point is not mapped, in which case the returned colour is undefined. */
279 bool CColouredOctoMap::getPointColour(const float x, const float y, const float z, uint8_t& r, uint8_t& g, uint8_t& b) const
280 {
281  octomap::OcTreeKey key;
282  if (PIMPL_GET_REF(ColorOcTree, m_octomap).coordToKeyChecked(octomap::point3d(x,y,z), key))
283  {
284  octomap::ColorOcTreeNode *node = PIMPL_GET_REF(ColorOcTree, m_octomap).search(key,0 /*depth*/);
285  if (!node) return false;
286 
287  const octomap::ColorOcTreeNode::Color &col = node->getColor();
288  r = col.r;
289  g = col.g;
290  b = col.b;
291  return true;
292  }
293  else return false;
294 }
295 
296 /** Manually update the colour of the voxel at (x,y,z) */
297 void CColouredOctoMap::updateVoxelColour(const double x, const double y, const double z, const uint8_t r, const uint8_t g, const uint8_t b)
298 {
299  switch (m_colour_method) {
300  case INTEGRATE:
301  PIMPL_GET_REF(ColorOcTree, m_octomap).integrateNodeColor(x,y,z,r,g,b);
302  break;
303  case SET:
304  PIMPL_GET_REF(ColorOcTree, m_octomap).setNodeColor(x,y,z,r,g,b);
305  break;
306  case AVERAGE:
307  PIMPL_GET_REF(ColorOcTree, m_octomap).averageNodeColor(x,y,z,r,g,b);
308  break;
309  default:
310  THROW_EXCEPTION("Invalid value found for 'm_colour_method'")
311  }
312 }
313 
314 
315 /** Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object. */
316 void CColouredOctoMap::getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const
317 {
318  // Go thru all voxels:
319 
320  //OcTreeVolume voxel; // current voxel, possibly transformed
321  octomap::ColorOcTree::tree_iterator it_end = PIMPL_GET_REF(ColorOcTree, m_octomap).end_tree();
322 
323  const unsigned char max_depth = 0; // all
324  const TColorf general_color = gl_obj.getColor();
325  const TColor general_color_u(general_color.R*255,general_color.G*255,general_color.B*255,general_color.A*255);
326 
327  gl_obj.clear();
328  gl_obj.reserveGridCubes( this->calcNumNodes() );
329 
330  gl_obj.resizeVoxelSets(2); // 2 sets of voxels: occupied & free
331 
332  gl_obj.showVoxels(VOXEL_SET_OCCUPIED, renderingOptions.visibleOccupiedVoxels );
333  gl_obj.showVoxels(VOXEL_SET_FREESPACE, renderingOptions.visibleFreeVoxels );
334 
335  const size_t nLeafs = this->getNumLeafNodes();
336  gl_obj.reserveVoxels(VOXEL_SET_OCCUPIED, nLeafs);
337  gl_obj.reserveVoxels(VOXEL_SET_FREESPACE, nLeafs);
338 
339  double xmin, xmax, ymin, ymax, zmin, zmax;
340  this->getMetricMin(xmin, ymin, zmin);
341  this->getMetricMax(xmax, ymax, zmax);
342 
343  for(octomap::ColorOcTree::tree_iterator it = PIMPL_GET_REF(ColorOcTree, m_octomap).begin_tree(max_depth);it!=it_end; ++it)
344  {
345  const octomap::point3d vx_center = it.getCoordinate();
346  const double vx_length = it.getSize();
347  const double L = 0.5*vx_length;
348 
349  if (it.isLeaf())
350  {
351  // voxels for leaf nodes
352  const double occ = it->getOccupancy();
353  if ( (occ>=0.5 && renderingOptions.generateOccupiedVoxels) ||
354  (occ<0.5 && renderingOptions.generateFreeVoxels) )
355  {
356  mrpt::utils::TColor vx_color;
357  octomap::ColorOcTreeNode::Color node_color = it->getColor();
358  vx_color = TColor(node_color.r, node_color.g, node_color.b);
359 
360  const size_t vx_set = (PIMPL_GET_REF(ColorOcTree, m_octomap).isNodeOccupied(*it)) ? VOXEL_SET_OCCUPIED:VOXEL_SET_FREESPACE;
361 
362  gl_obj.push_back_Voxel(vx_set,COctoMapVoxels::TVoxel( TPoint3D(vx_center.x(),vx_center.y(),vx_center.z()) ,vx_length, vx_color) );
363  }
364  }
365  else if (renderingOptions.generateGridLines)
366  {
367  // Not leaf-nodes:
368  const mrpt::math::TPoint3D pt_min ( vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
369  const mrpt::math::TPoint3D pt_max ( vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
370  gl_obj.push_back_GridCube( COctoMapVoxels::TGridCube( pt_min, pt_max ) );
371  }
372  } // end for each voxel
373 
374  // if we use transparency, sort cubes by "Z" as an approximation to far-to-near render ordering:
375  if (gl_obj.isCubeTransparencyEnabled())
376  gl_obj.sort_voxels_by_z();
377 
378  // Set bounding box:
379  {
380  mrpt::math::TPoint3D bbmin, bbmax;
381  this->getMetricMin(bbmin.x,bbmin.y,bbmin.z);
382  this->getMetricMax(bbmax.x,bbmax.y,bbmax.z);
383  gl_obj.setBoundingBox(bbmin, bbmax);
384  }
385 }
386 
387 void CColouredOctoMap::insertRay(const float end_x, const float end_y, const float end_z, const float sensor_x, const float sensor_y, const float sensor_z)
388 {
389  PIMPL_GET_REF(ColorOcTree, m_octomap).insertRay(octomap::point3d(sensor_x, sensor_y, sensor_z), octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange, insertionOptions.pruning);
390 }
391 void CColouredOctoMap::updateVoxel(const double x, const double y, const double z, bool occupied)
392 {
393  PIMPL_GET_REF(ColorOcTree, m_octomap).updateNode(x, y, z, occupied);
394 }
395 bool CColouredOctoMap::isPointWithinOctoMap(const float x, const float y, const float z) const
396 {
397  octomap::OcTreeKey key;
398  return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).coordToKeyChecked(octomap::point3d(x, y, z), key);
399 }
400 
401 double CColouredOctoMap::getResolution() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getResolution(); }
402 unsigned int CColouredOctoMap::getTreeDepth() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getTreeDepth(); }
403 size_t CColouredOctoMap::size() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).size(); }
404 size_t CColouredOctoMap::memoryUsage() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryUsage(); }
405 size_t CColouredOctoMap::memoryUsageNode() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryUsageNode(); }
406 size_t CColouredOctoMap::memoryFullGrid() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryFullGrid(); }
407 double CColouredOctoMap::volume() { return PIMPL_GET_REF(ColorOcTree, m_octomap).volume(); }
408 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z) { return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricSize(x, y, z); }
409 void CColouredOctoMap::getMetricSize(double& x, double& y, double& z) const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricSize(x, y, z); }
410 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z) { return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricMin(x, y, z); }
411 void CColouredOctoMap::getMetricMin(double& x, double& y, double& z) const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricMin(x, y, z); }
412 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z) { return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricMax(x, y, z); }
413 void CColouredOctoMap::getMetricMax(double& x, double& y, double& z) const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricMax(x, y, z); }
414 size_t CColouredOctoMap::calcNumNodes() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).calcNumNodes(); }
415 size_t CColouredOctoMap::getNumLeafNodes() const { return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getNumLeafNodes(); }
416 void CColouredOctoMap::setOccupancyThres(double prob) { PIMPL_GET_REF(ColorOcTree, m_octomap).setOccupancyThres(prob) ; }
417 void CColouredOctoMap::setProbHit(double prob) { PIMPL_GET_REF(ColorOcTree, m_octomap).setProbHit(prob); }
418 void CColouredOctoMap::setProbMiss(double prob) { PIMPL_GET_REF(ColorOcTree, m_octomap).setProbMiss(prob); }
419 void CColouredOctoMap::setClampingThresMin(double thresProb) { PIMPL_GET_REF(ColorOcTree, m_octomap).setClampingThresMin(thresProb); }
420 void CColouredOctoMap::setClampingThresMax(double thresProb) { PIMPL_GET_REF(ColorOcTree, m_octomap).setClampingThresMax(thresProb); }
421 double CColouredOctoMap::getOccupancyThres() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getOccupancyThres(); }
422 float CColouredOctoMap::getOccupancyThresLog() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getOccupancyThresLog(); }
423 double CColouredOctoMap::getProbHit() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbHit(); }
424 float CColouredOctoMap::getProbHitLog() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbHitLog(); }
425 double CColouredOctoMap::getProbMiss() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbMiss(); }
426 float CColouredOctoMap::getProbMissLog() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbMissLog(); }
427 double CColouredOctoMap::getClampingThresMin() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMin(); }
428 float CColouredOctoMap::getClampingThresMinLog() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMinLog(); }
429 double CColouredOctoMap::getClampingThresMax() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMax(); }
430 float CColouredOctoMap::getClampingThresMaxLog() const { return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMaxLog(); }
431 void CColouredOctoMap::internal_clear() { PIMPL_GET_REF(ColorOcTree, m_octomap).clear(); }
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:113
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)
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Definition: zip.h:16
GLdouble GLdouble z
Definition: glext.h:3734
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: NULL) Read takeIntoAccountSensorPoseOnRobot
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
#define THROW_EXCEPTION(msg)
Scalar * iterator
Definition: eigen_plugins.h:23
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
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.
double z
X,Y,Z coordinates.
void clear()
Clears everything.
GLsizei GLsizei GLuint * obj
Definition: glext.h:3902
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:113
This class allows loading and storing values and vectors of different types from a configuration text...
unsigned char uint8_t
Definition: rptypes.h:43
void readFromStream(mrpt::utils::CStream &in, int version)
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void push_back_GridCube(const TGridCube &c)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, 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:427
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
std::string BASE_IMPEXP getTempFileName()
Returns the name of a proposed temporary file name.
Definition: filesystem.cpp:273
mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts
Observations insertion options.
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:595
#define PIMPL_GET_CONSTREF(_TYPE, _VAR_NAME)
Definition: pimpl.h:76
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
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:5575
A RGB color - 8bit.
Definition: TColor.h:26
This namespace contains representation of robot actions and observations.
GLubyte GLubyte b
Definition: glext.h:5575
PIMPL_IMPLEMENT(octomap::ColorOcTree)
int version
Definition: mrpt_jpeglib.h:898
A memory buffer (implements CStream) which can be itself serialized.
Definition: CMemoryChunk.h:27
GLsizei const GLchar ** string
Definition: glext.h:3919
#define PIMPL_GET_REF(_TYPE, _VAR_NAME)
Definition: pimpl.h:75
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
The info of each grid block.
void push_back_Voxel(const size_t set_index, const TVoxel &v)
GLclampd zmax
Definition: glext.h:6808
#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...
GLdouble GLdouble GLdouble r
Definition: glext.h:3618
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
Declares a virtual base class for all metric maps storage classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:72
Declares a class that represents any robot&#39;s observation.
void resizeVoxelSets(const size_t nVoxelSets)
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::utils::CSerializable) is of t...
Definition: CObject.h:93
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
GLuint in
Definition: glext.h:6301
The namespace for 3D scene representation and rendering.
GLsizei GLsizei GLchar * source
Definition: glext.h:3908
A RGB color - floats in the range [0,1].
Definition: TColor.h:80
bool BASE_IMPEXP deleteFile(const std::string &fileName)
Deletes a single file.
Definition: filesystem.cpp:175
GLenum GLint GLint y
Definition: glext.h:3516
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:3779
GLenum GLint x
Definition: glext.h:3516
Lightweight 3D point.
virtual void load() const MRPT_OVERRIDE
Makes sure all images and other fields which may be externally stored are loaded in memory...
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 meters)
bool loadBufferFromFile(const std::string &file_name)
Loads the entire buffer from a file *.
size_t size() const
Returns the number of stored points in the map.
bool isCubeTransparencyEnabled() const
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
static CPointCloudColouredPtr Create()
mrpt::utils::TColorf getColor() const
Returns the object color property as a TColorf.
const POINTSMAP * buildAuxPointsMap(const void *options=NULL) const
Returns a cached points map representing this laser scan, building it upon the first call...



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019