Main MRPT website > C++ reference for 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-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 
13 #include <mrpt/maps/CPointsMap.h>
16 
20 
21 #include <mrpt/system/filesystem.h>
24 
25 using namespace std;
26 using namespace mrpt;
27 using namespace mrpt::maps;
28 using namespace mrpt::obs;
29 using namespace mrpt::utils;
30 using namespace mrpt::poses;
31 using namespace mrpt::opengl;
32 using namespace mrpt::math;
33 
34 // =========== Begin of Map definition ============
36  "CColouredOctoMap,colourOctoMap,colorOctoMap", mrpt::maps::CColouredOctoMap)
37 
39 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(
41  const std::string& sectionNamePrefix)
42 {
43  // [<sectionNamePrefix>+"_creationOpts"]
44  const std::string sSectCreation =
45  sectionNamePrefix + string("_creationOpts");
46  MRPT_LOAD_CONFIG_VAR(resolution, double, source, sSectCreation);
47 
48  insertionOpts.loadFromConfigFile(
49  source, sectionNamePrefix + string("_insertOpts"));
50  likelihoodOpts.loadFromConfigFile(
51  source, sectionNamePrefix + string("_likelihoodOpts"));
52 }
53 
54 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(
55  mrpt::utils::CStream& out) const
56 {
57  LOADABLEOPTS_DUMP_VAR(resolution, double);
58 
59  this->insertionOpts.dumpToTextStream(out);
60  this->likelihoodOpts.dumpToTextStream(out);
61 }
62 
63 mrpt::maps::CMetricMap* CColouredOctoMap::internal_CreateFromMapDefinition(
65 {
67  *dynamic_cast<const CColouredOctoMap::TMapDefinition*>(&_def);
69  obj->insertionOptions = def.insertionOpts;
70  obj->likelihoodOptions = def.likelihoodOpts;
71  return obj;
72 }
73 // =========== End of Map definition Block =========
74 
76 
77 /*---------------------------------------------------------------
78  Constructor
79  ---------------------------------------------------------------*/
80 CColouredOctoMap::CColouredOctoMap(const double resolution)
81  : COctoMapBase<octomap::ColorOcTree, octomap::ColorOcTreeNode>(resolution),
82  m_colour_method(INTEGRATE)
83 {
84 }
85 
86 /*---------------------------------------------------------------
87  Destructor
88  ---------------------------------------------------------------*/
89 CColouredOctoMap::~CColouredOctoMap() {}
90 /*---------------------------------------------------------------
91  writeToStream
92  Implements the writing to a CStream capability of
93  CSerializable objects
94  ---------------------------------------------------------------*/
95 void CColouredOctoMap::writeToStream(
96  mrpt::utils::CStream& out, int* version) const
97 {
98  if (version)
99  *version = 2;
100  else
101  {
102  this->likelihoodOptions.writeToStream(out);
103  this->renderingOptions.writeToStream(out); // Added in v1
104  out << genericMapParams; // v2
105 
106  CMemoryChunk chunk;
107  const string tmpFil = mrpt::system::getTempFileName();
108  const_cast<octomap::ColorOcTree*>(&m_octomap)->writeBinary(tmpFil);
109  chunk.loadBufferFromFile(tmpFil);
110  mrpt::system::deleteFile(tmpFil);
111  out << chunk;
112  }
113 }
114 
115 /*---------------------------------------------------------------
116  readFromStream
117  Implements the reading from a CStream capability of
118  CSerializable objects
119  ---------------------------------------------------------------*/
120 void CColouredOctoMap::readFromStream(mrpt::utils::CStream& in, int version)
121 {
122  switch (version)
123  {
124  case 0:
125  case 1:
126  case 2:
127  {
128  this->likelihoodOptions.readFromStream(in);
129  if (version >= 1) this->renderingOptions.readFromStream(in);
130  if (version >= 2) in >> genericMapParams;
131 
132  this->clear();
133 
134  CMemoryChunk chunk;
135  in >> chunk;
136 
137  if (chunk.getTotalBytesCount())
138  {
139  const string tmpFil = mrpt::system::getTempFileName();
140  if (!chunk.saveBufferToFile(tmpFil))
141  THROW_EXCEPTION("Error saving temporary file");
142  m_octomap.readBinary(tmpFil);
143  mrpt::system::deleteFile(tmpFil);
144  }
145  }
146  break;
147  default:
149  };
150 }
151 
152 /*---------------------------------------------------------------
153  insertObservation
154  ---------------------------------------------------------------*/
155 bool CColouredOctoMap::internal_insertObservation(
156  const mrpt::obs::CObservation* obs, const CPose3D* robotPose)
157 {
158  octomap::point3d sensorPt;
159  octomap::Pointcloud scan;
160 
161  CPose3D robotPose3D;
162  if (robotPose) // Default values are (0,0,0)
163  robotPose3D = (*robotPose);
164 
166  {
167  /********************************************************************
168  OBSERVATION TYPE: CObservation2DRangeScan
169  ********************************************************************/
170  const CObservation2DRangeScan* o =
171  static_cast<const CObservation2DRangeScan*>(obs);
172 
173  // Build a points-map representation of the points from the scan
174  // (coordinates are wrt the robot base)
175 
176  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
177  CPose3D sensorPose(UNINITIALIZED_POSE);
178  sensorPose.composeFrom(robotPose3D, o->sensorPose);
179  sensorPt =
180  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
181 
182  const CPointsMap* scanPts =
184  const size_t nPts = scanPts->size();
185 
186  // Transform 3D point cloud:
187  scan.reserve(nPts);
188 
190  for (size_t i = 0; i < nPts; i++)
191  {
192  // Load the next point:
193  scanPts->getPointFast(i, pt.x, pt.y, pt.z);
194 
195  // Translation:
196  double gx, gy, gz;
197  robotPose3D.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
198 
199  // Add to this map:
200  scan.push_back(gx, gy, gz);
201  }
202 
203  // Insert rays:
204  m_octomap.insertPointCloud(
205  scan, sensorPt, insertionOptions.maxrange,
206  insertionOptions.pruning);
207  return true;
208  }
209  else if (IS_CLASS(obs, CObservation3DRangeScan))
210  {
211  /********************************************************************
212  OBSERVATION TYPE: CObservation3DRangeScan
213  ********************************************************************/
214  const CObservation3DRangeScan* o =
215  static_cast<const CObservation3DRangeScan*>(obs);
216 
217  o->load(); // Just to make sure the points are loaded from an external
218  // source, if that's the case...
219 
220  // Project 3D points & color:
222  mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
223  T3DPointsProjectionParams proj_params;
224  proj_params.PROJ3D_USE_LUT = true;
225  proj_params.robotPoseInTheWorld = robotPose;
226  const_cast<CObservation3DRangeScan*>(o)
227  ->project3DPointsFromDepthImageInto(*pts, proj_params);
228 
229  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
230  CPose3D sensorPose(UNINITIALIZED_POSE);
231  sensorPose.composeFrom(robotPose3D, o->sensorPose);
232  sensorPt =
233  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
234 
235  const size_t sizeRangeScan = pts->size();
236  scan.reserve(sizeRangeScan);
237 
238  for (size_t i = 0; i < sizeRangeScan; i++)
239  {
241  pts->getPoint(i);
242 
243  // Add to this map:
244  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
245  scan.push_back(pt.x, pt.y, pt.z);
246  }
247 
248  // Insert rays:
249  octomap::KeySet free_cells, occupied_cells;
250  m_octomap.computeUpdate(
251  scan, sensorPt, free_cells, occupied_cells,
252  insertionOptions.maxrange);
253 
254  // insert data into tree -----------------------
255  for (octomap::KeySet::iterator it = free_cells.begin();
256  it != free_cells.end(); ++it)
257  {
258  m_octomap.updateNode(*it, false, false);
259  }
260  for (octomap::KeySet::iterator it = occupied_cells.begin();
261  it != occupied_cells.end(); ++it)
262  {
263  m_octomap.updateNode(*it, true, false);
264  }
265 
266  // Update color -----------------------
267  const float colF2B = 255.0f;
268  for (size_t i = 0; i < sizeRangeScan; i++)
269  {
271  pts->getPoint(i);
272 
273  // Add to this map:
274  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
275  this->updateVoxelColour(
276  pt.x, pt.y, pt.z, uint8_t(pt.R * colF2B),
277  uint8_t(pt.G * colF2B), uint8_t(pt.B * colF2B));
278  }
279 
280  // TODO: does pruning make sense if we used "lazy_eval"?
281  if (insertionOptions.pruning) m_octomap.prune();
282 
283  return true;
284  }
285 
286  return false;
287 }
288 
289 /** Get the RGB colour of a point
290 * \return false if the point is not mapped, in which case the returned colour is
291 * undefined. */
292 bool CColouredOctoMap::getPointColour(
293  const float x, const float y, const float z, uint8_t& r, uint8_t& g,
294  uint8_t& b) const
295 {
296  octomap::OcTreeKey key;
297  if (m_octomap.coordToKeyChecked(octomap::point3d(x, y, z), key))
298  {
299  octomap::ColorOcTreeNode* node = m_octomap.search(key, 0 /*depth*/);
300  if (!node) return false;
301 
302  const octomap::ColorOcTreeNode::Color& col = node->getColor();
303  r = col.r;
304  g = col.g;
305  b = col.b;
306  return true;
307  }
308  else
309  return false;
310 }
311 
312 /** Manually update the colour of the voxel at (x,y,z) */
313 void CColouredOctoMap::updateVoxelColour(
314  const double x, const double y, const double z, const uint8_t r,
315  const uint8_t g, const uint8_t b)
316 {
317  switch (m_colour_method)
318  {
319  case INTEGRATE:
320  m_octomap.integrateNodeColor(x, y, z, r, g, b);
321  break;
322  case SET:
323  m_octomap.setNodeColor(x, y, z, r, g, b);
324  break;
325  case AVERAGE:
326  m_octomap.averageNodeColor(x, y, z, r, g, b);
327  break;
328  default:
329  THROW_EXCEPTION("Invalid value found for 'm_colour_method'")
330  }
331 }
332 
333 /** Builds a renderizable representation of the octomap as a
334  * mrpt::opengl::COctoMapVoxels object. */
335 void CColouredOctoMap::getAsOctoMapVoxels(
336  mrpt::opengl::COctoMapVoxels& gl_obj) const
337 {
338  // Go thru all voxels:
339 
340  // OcTreeVolume voxel; // current voxel, possibly transformed
341  octomap::ColorOcTree::tree_iterator it_end = m_octomap.end_tree();
342 
343  const unsigned char max_depth = 0; // all
344  const TColorf general_color = gl_obj.getColor();
345  const TColor general_color_u(
346  general_color.R * 255, general_color.G * 255, general_color.B * 255,
347  general_color.A * 255);
348 
349  gl_obj.clear();
350  gl_obj.reserveGridCubes(this->calcNumNodes());
351 
352  gl_obj.resizeVoxelSets(2); // 2 sets of voxels: occupied & free
353 
354  gl_obj.showVoxels(
355  VOXEL_SET_OCCUPIED, renderingOptions.visibleOccupiedVoxels);
356  gl_obj.showVoxels(VOXEL_SET_FREESPACE, renderingOptions.visibleFreeVoxels);
357 
358  const size_t nLeafs = this->getNumLeafNodes();
359  gl_obj.reserveVoxels(VOXEL_SET_OCCUPIED, nLeafs);
360  gl_obj.reserveVoxels(VOXEL_SET_FREESPACE, nLeafs);
361 
362  double xmin, xmax, ymin, ymax, zmin, zmax;
363  this->getMetricMin(xmin, ymin, zmin);
364  this->getMetricMax(xmax, ymax, zmax);
365 
366  for (octomap::ColorOcTree::tree_iterator it =
367  m_octomap.begin_tree(max_depth);
368  it != it_end; ++it)
369  {
370  const octomap::point3d vx_center = it.getCoordinate();
371  const double vx_length = it.getSize();
372  const double L = 0.5 * vx_length;
373 
374  if (it.isLeaf())
375  {
376  // voxels for leaf nodes
377  const double occ = it->getOccupancy();
378  if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
379  (occ < 0.5 && renderingOptions.generateFreeVoxels))
380  {
381  mrpt::utils::TColor vx_color;
382  octomap::ColorOcTreeNode::Color node_color = it->getColor();
383  vx_color = TColor(node_color.r, node_color.g, node_color.b);
384 
385  const size_t vx_set = (m_octomap.isNodeOccupied(*it))
388 
389  gl_obj.push_back_Voxel(
390  vx_set,
392  TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
393  vx_length, vx_color));
394  }
395  }
396  else if (renderingOptions.generateGridLines)
397  {
398  // Not leaf-nodes:
399  const mrpt::math::TPoint3D pt_min(
400  vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
401  const mrpt::math::TPoint3D pt_max(
402  vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
403  gl_obj.push_back_GridCube(
404  COctoMapVoxels::TGridCube(pt_min, pt_max));
405  }
406  } // end for each voxel
407 
408  // if we use transparency, sort cubes by "Z" as an approximation to
409  // far-to-near render ordering:
410  if (gl_obj.isCubeTransparencyEnabled()) gl_obj.sort_voxels_by_z();
411 
412  // Set bounding box:
413  {
414  mrpt::math::TPoint3D bbmin, bbmax;
415  this->getMetricMin(bbmin.x, bbmin.y, bbmin.z);
416  this->getMetricMax(bbmax.x, bbmax.y, bbmax.z);
417  gl_obj.setBoundingBox(bbmin, bbmax);
418  }
419 }
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
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.
GLdouble GLdouble z
Definition: glext.h:3872
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.
#define THROW_EXCEPTION(msg)
virtual void writeToStream(mrpt::utils::CStream &out, int *getVersion) const =0
Introduces a pure virtual method responsible for writing to a CStream.
Scalar * iterator
Definition: eigen_plugins.h:26
#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.
void clear()
Clears everything.
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:189
This class allows loading and storing values and vectors of different types from a configuration text...
unsigned char uint8_t
Definition: rptypes.h:41
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:48
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void push_back_GridCube(const TGridCube &c)
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:63
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
std::string getTempFileName()
Returns the name of a proposed temporary file name.
Definition: filesystem.cpp:281
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
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:639
#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:6279
A RGB color - 8bit.
Definition: TColor.h:25
This namespace contains representation of robot actions and observations.
GLubyte GLubyte b
Definition: glext.h:6279
double x
X,Y,Z coordinates.
A memory buffer (implements CStream) which can be itself serialized.
Definition: CMemoryChunk.h:24
GLsizei const GLchar ** string
Definition: glext.h:4101
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:7918
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: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:55
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
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:453
#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:103
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
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
A RGB color - floats in the range [0,1].
Definition: TColor.h:78
bool deleteFile(const std::string &fileName)
Deletes a single file.
Definition: filesystem.cpp:179
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 ...
#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...
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 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.
Definition: CPointsMap.h:385
bool isCubeTransparencyEnabled() const
std::shared_ptr< CPointCloudColoured > Ptr
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...
mrpt::utils::TColorf getColor() const
Returns the object color property as a TColorf.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019