Main MRPT website > C++ reference for MRPT 1.9.9
COctoMapBase_impl.h
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 // This file is to be included from <mrpt/maps/COctoMapBase.h>
14 #include <mrpt/maps/CPointsMap.h>
15 
16 namespace mrpt
17 {
18 namespace maps
19 {
20 template <class OCTREE, class OCTREE_NODE>
23  const mrpt::obs::CObservation* obs,
24  const mrpt::poses::CPose3D* robotPose, octomap::point3d& sensorPt,
25  octomap::Pointcloud& scan) const
26 {
27  using namespace mrpt::poses;
28  using namespace mrpt::obs;
29 
30  scan.clear();
31 
32  CPose3D robotPose3D;
33  if (robotPose) // Default values are (0,0,0)
34  robotPose3D = (*robotPose);
35 
37  {
38  /********************************************************************
39  OBSERVATION TYPE: CObservation2DRangeScan
40  ********************************************************************/
41  const CObservation2DRangeScan* o =
42  static_cast<const CObservation2DRangeScan*>(obs);
43 
44  // Build a points-map representation of the points from the scan
45  // (coordinates are wrt the robot base)
46 
47  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
48  CPose3D sensorPose(UNINITIALIZED_POSE);
49  sensorPose.composeFrom(robotPose3D, o->sensorPose);
50  sensorPt =
51  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
52 
53  const CPointsMap* scanPts =
55  const size_t nPts = scanPts->size();
56 
57  // Transform 3D point cloud:
58  scan.reserve(nPts);
59 
61  for (size_t i = 0; i < nPts; i++)
62  {
63  // Load the next point:
64  scanPts->getPointFast(i, pt.x, pt.y, pt.z);
65 
66  // Translation:
67  double gx, gy, gz;
68  robotPose3D.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
69 
70  // Add to this map:
71  scan.push_back(gx, gy, gz);
72  }
73  return true;
74  }
75  else if (IS_CLASS(obs, CObservation3DRangeScan))
76  {
77  /********************************************************************
78  OBSERVATION TYPE: CObservation3DRangeScan
79  ********************************************************************/
80  const CObservation3DRangeScan* o =
81  static_cast<const CObservation3DRangeScan*>(obs);
82 
83  // Build a points-map representation of the points from the scan
84  // (coordinates are wrt the robot base)
85  if (!o->hasPoints3D) return false;
86 
87  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
88  CPose3D sensorPose(UNINITIALIZED_POSE);
89  sensorPose.composeFrom(robotPose3D, o->sensorPose);
90  sensorPt =
91  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
92 
93  o->load(); // Just to make sure the points are loaded from an external
94  // source, if that's the case...
95  const size_t sizeRangeScan = o->points3D_x.size();
96 
97  // Transform 3D point cloud:
98  scan.reserve(sizeRangeScan);
99 
100  // For quicker access to values as "float" instead of "doubles":
102  robotPose3D.getHomogeneousMatrix(H);
103  const float m00 = H.get_unsafe(0, 0);
104  const float m01 = H.get_unsafe(0, 1);
105  const float m02 = H.get_unsafe(0, 2);
106  const float m03 = H.get_unsafe(0, 3);
107  const float m10 = H.get_unsafe(1, 0);
108  const float m11 = H.get_unsafe(1, 1);
109  const float m12 = H.get_unsafe(1, 2);
110  const float m13 = H.get_unsafe(1, 3);
111  const float m20 = H.get_unsafe(2, 0);
112  const float m21 = H.get_unsafe(2, 1);
113  const float m22 = H.get_unsafe(2, 2);
114  const float m23 = H.get_unsafe(2, 3);
115 
117  for (size_t i = 0; i < sizeRangeScan; i++)
118  {
119  pt.x = o->points3D_x[i];
120  pt.y = o->points3D_y[i];
121  pt.z = o->points3D_z[i];
122 
123  // Valid point?
124  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
125  {
126  // Translation:
127  const float gx = m00 * pt.x + m01 * pt.y + m02 * pt.z + m03;
128  const float gy = m10 * pt.x + m11 * pt.y + m12 * pt.z + m13;
129  const float gz = m20 * pt.x + m21 * pt.y + m22 * pt.z + m23;
130 
131  // Add to this map:
132  scan.push_back(gx, gy, gz);
133  }
134  }
135  return true;
136  }
137 
138  return false;
139 }
140 
141 template <class OCTREE, class OCTREE_NODE>
143 {
144  return m_octomap.size() == 1;
145 }
146 
147 template <class OCTREE, class OCTREE_NODE>
149  const std::string& filNamePrefix) const
150 {
151  MRPT_START
152 
153  // Save as 3D Scene:
154  {
157  mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
158 
159  this->getAs3DObject(obj3D);
160 
161  scene.insert(obj3D);
162 
163  const std::string fil = filNamePrefix + std::string("_3D.3Dscene");
165  f << scene;
166  }
167 
168  // Save as ".bt" file (a binary format from the octomap lib):
169  {
170  const std::string fil = filNamePrefix + std::string("_binary.bt");
171  const_cast<OCTREE*>(&m_octomap)->writeBinary(fil);
172  }
173  MRPT_END
174 }
175 
176 template <class OCTREE, class OCTREE_NODE>
178  const mrpt::obs::CObservation* obs, const mrpt::poses::CPose3D& takenFrom)
179 {
180  octomap::point3d sensorPt;
181  octomap::Pointcloud scan;
182 
183  if (!internal_build_PointCloud_for_observation(
184  obs, &takenFrom, sensorPt, scan))
185  return 0; // Nothing to do.
186 
187  octomap::OcTreeKey key;
188  const size_t N = scan.size();
189 
190  double log_lik = 0;
191  for (size_t i = 0; i < N; i += likelihoodOptions.decimation)
192  {
193  if (m_octomap.coordToKeyChecked(scan.getPoint(i), key))
194  {
195  octree_node_t* node = m_octomap.search(key, 0 /*depth*/);
196  if (node) log_lik += std::log(node->getOccupancy());
197  }
198  }
199 
200  return log_lik;
201 }
202 
203 template <class OCTREE, class OCTREE_NODE>
205  const float x, const float y, const float z, double& prob_occupancy) const
206 {
207  octomap::OcTreeKey key;
208  if (m_octomap.coordToKeyChecked(octomap::point3d(x, y, z), key))
209  {
210  octree_node_t* node = m_octomap.search(key, 0 /*depth*/);
211  if (!node) return false;
212 
213  prob_occupancy = node->getOccupancy();
214  return true;
215  }
216  else
217  return false;
218 }
219 
220 template <class OCTREE, class OCTREE_NODE>
222  const CPointsMap& ptMap, const float sensor_x, const float sensor_y,
223  const float sensor_z)
224 {
225  MRPT_START
226  const octomap::point3d sensorPt(sensor_x, sensor_y, sensor_z);
227  size_t N;
228  const float *xs, *ys, *zs;
229  ptMap.getPointsBuffer(N, xs, ys, zs);
230  for (size_t i = 0; i < N; i++)
231  m_octomap.insertRay(
232  sensorPt, octomap::point3d(xs[i], ys[i], zs[i]),
233  insertionOptions.maxrange, insertionOptions.pruning);
234  MRPT_END
235 }
236 
237 template <class OCTREE, class OCTREE_NODE>
239  const mrpt::math::TPoint3D& origin, const mrpt::math::TPoint3D& direction,
240  mrpt::math::TPoint3D& end, bool ignoreUnknownCells, double maxRange) const
241 {
242  octomap::point3d _end;
243 
244  const bool ret = m_octomap.castRay(
245  octomap::point3d(origin.x, origin.y, origin.z),
246  octomap::point3d(direction.x, direction.y, direction.z), _end,
247  ignoreUnknownCells, maxRange);
248 
249  end.x = _end.x();
250  end.y = _end.y();
251  end.z = _end.z();
252  return ret;
253 }
254 
255 /*---------------------------------------------------------------
256  TInsertionOptions
257  ---------------------------------------------------------------*/
258 template <class OCTREE, class OCTREE_NODE>
261  : maxrange(-1.),
262  pruning(true),
263  m_parent(&parent),
264  // Default values from octomap:
265  occupancyThres(0.5),
266  probHit(0.7),
267  probMiss(0.4),
268  clampingThresMin(0.1192),
269  clampingThresMax(0.971)
270 {
271 }
272 
273 template <class OCTREE, class OCTREE_NODE>
275  : maxrange(-1.),
276  pruning(true),
277  m_parent(nullptr),
278  // Default values from octomap:
279  occupancyThres(0.5),
280  probHit(0.7),
281  probMiss(0.4),
282  clampingThresMin(0.1192),
283  clampingThresMax(0.971)
284 {
285 }
286 
287 template <class OCTREE, class OCTREE_NODE>
289  : decimation(1)
290 {
291 }
292 
293 template <class OCTREE, class OCTREE_NODE>
295  mrpt::utils::CStream& out) const
296 {
297  const int8_t version = 0;
298  out << version;
299  out << decimation;
300 }
301 
302 template <class OCTREE, class OCTREE_NODE>
305 {
306  int8_t version;
307  in >> version;
308  switch (version)
309  {
310  case 0:
311  {
312  in >> decimation;
313  }
314  break;
315  default:
317  }
318 }
319 
320 /*---------------------------------------------------------------
321  dumpToTextStream
322  ---------------------------------------------------------------*/
323 template <class OCTREE, class OCTREE_NODE>
325  mrpt::utils::CStream& out) const
326 {
327  out.printf(
328  "\n----------- [COctoMapBase<>::TInsertionOptions] ------------ \n\n");
329 
330  LOADABLEOPTS_DUMP_VAR(maxrange, double);
331  LOADABLEOPTS_DUMP_VAR(pruning, bool);
332 
333  LOADABLEOPTS_DUMP_VAR(getOccupancyThres(), double);
334  LOADABLEOPTS_DUMP_VAR(getProbHit(), double);
335  LOADABLEOPTS_DUMP_VAR(getProbMiss(), double);
336  LOADABLEOPTS_DUMP_VAR(getClampingThresMin(), double);
337  LOADABLEOPTS_DUMP_VAR(getClampingThresMax(), double);
338 
339  out.printf("\n");
340 }
341 
342 template <class OCTREE, class OCTREE_NODE>
344  mrpt::utils::CStream& out) const
345 {
346  out.printf(
347  "\n----------- [COctoMapBase<>::TLikelihoodOptions] ------------ \n\n");
348 
349  LOADABLEOPTS_DUMP_VAR(decimation, int);
350 }
351 
352 /*---------------------------------------------------------------
353  loadFromConfigFile
354  ---------------------------------------------------------------*/
355 template <class OCTREE, class OCTREE_NODE>
357  const mrpt::utils::CConfigFileBase& iniFile, const std::string& section)
358 {
359  MRPT_LOAD_CONFIG_VAR(maxrange, double, iniFile, section);
360  MRPT_LOAD_CONFIG_VAR(pruning, bool, iniFile, section);
361 
362  MRPT_LOAD_CONFIG_VAR(occupancyThres, double, iniFile, section);
363  MRPT_LOAD_CONFIG_VAR(probHit, double, iniFile, section);
364  MRPT_LOAD_CONFIG_VAR(probMiss, double, iniFile, section);
365  MRPT_LOAD_CONFIG_VAR(clampingThresMin, double, iniFile, section);
366  MRPT_LOAD_CONFIG_VAR(clampingThresMax, double, iniFile, section);
367 
368  // Set loaded options into the actual octomap object, if any:
369  this->setOccupancyThres(occupancyThres);
370  this->setProbHit(probHit);
371  this->setProbMiss(probMiss);
372  this->setClampingThresMin(clampingThresMin);
373  this->setClampingThresMax(clampingThresMax);
374 }
375 
376 template <class OCTREE, class OCTREE_NODE>
378  const mrpt::utils::CConfigFileBase& iniFile, const std::string& section)
379 {
380  MRPT_LOAD_CONFIG_VAR(decimation, int, iniFile, section);
381 }
382 
383 /* COctoMapColoured */
384 template <class OCTREE, class OCTREE_NODE>
386  mrpt::utils::CStream& out) const
387 {
388  const int8_t version = 0;
389  out << version;
390  out << generateGridLines << generateOccupiedVoxels << visibleOccupiedVoxels
391  << generateFreeVoxels << visibleFreeVoxels;
392 }
393 
394 template <class OCTREE, class OCTREE_NODE>
397 {
398  int8_t version;
399  in >> version;
400  switch (version)
401  {
402  case 0:
403  {
404  in >> generateGridLines >> generateOccupiedVoxels >>
405  visibleOccupiedVoxels >> generateFreeVoxels >>
406  visibleFreeVoxels;
407  }
408  break;
409  default:
411  }
412 }
413 
414 } // End of namespace
415 } // End of namespace
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
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...
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
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.
signed char int8_t
Definition: rptypes.h:40
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
octomap::OcTreeNode octree_node_t
The type of nodes in the octree, in the "octomap" library.
Definition: COctoMapBase.h:56
This class allows loading and storing values and vectors of different types from a configuration text...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:48
TLikelihoodOptions()
Initilization of default parameters.
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
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream.
A numeric matrix of compile-time fixed size.
Lightweight 3D point (float version).
#define MRPT_END
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
This CStream derived class allow using a file as a write-only, binary stream.
bool internal_build_PointCloud_for_observation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const
Builds the list of 3D points in global coordinates for a generic observation.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
GLuint GLuint end
Definition: glext.h:3528
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:32
This namespace contains representation of robot actions and observations.
double x
X,Y,Z coordinates.
TInsertionOptions()
Especial constructor, not attached to a real COctoMap object: used only in limited situations...
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream.
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
Definition: glext.h:4101
bool castRay(const mrpt::math::TPoint3D &origin, const mrpt::math::TPoint3D &direction, mrpt::math::TPoint3D &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
Performs raycasting in 3d, similar to computeRay().
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
virtual bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
#define MRPT_START
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
void getPointsBuffer(size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs) const
Provides a direct access to points buffer, or nullptr if there is no points in the map...
Definition: CPointsMap.cpp:259
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 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
void insertPointCloud(const CPointsMap &ptMap, const float sensor_x, const float sensor_y, const float sensor_z)
Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the s...
GLuint in
Definition: glext.h:7274
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
Definition: COpenGLScene.h:60
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream.
GLenum GLint GLint y
Definition: glext.h:3538
#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.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
void insert(const CRenderizable::Ptr &newObject, const std::string &viewportName=std::string("main"))
Insert a new object into the scene, in the given viewport (by default, into the "main" viewport)...
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:385
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
Definition: CPose3D.h:221
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
Definition: CStream.cpp:597
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: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019