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-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 // This file is to be included from <mrpt/maps/COctoMapBase.h>
14 #include <mrpt/maps/CPointsMap.h>
16 
17 namespace mrpt::maps
18 {
19 
20 template <class OCTREE, class OCTREE_NODE>
21 struct mrpt::maps::COctoMapBase<OCTREE, OCTREE_NODE>::Impl
22 {
23  OCTREE m_octomap;
24 };
25 
26 template <class OCTREE, class OCTREE_NODE>
28  : insertionOptions(*this),
29  m_impl(new Impl({resolution}))
30 {}
31 
32 template <class OCTREE, class OCTREE_NODE>
33 template <class octomap_point3d, class octomap_pointcloud>
34 bool COctoMapBase<OCTREE, OCTREE_NODE>::
35  internal_build_PointCloud_for_observation(
36  const mrpt::obs::CObservation* obs,
37  const mrpt::poses::CPose3D* robotPose, octomap_point3d& sensorPt,
38  octomap_pointcloud& scan) const
39 {
40  using namespace mrpt::poses;
41  using namespace mrpt::obs;
42 
43  scan.clear();
44 
45  CPose3D robotPose3D;
46  if (robotPose) // Default values are (0,0,0)
47  robotPose3D = (*robotPose);
48 
50  {
51  /********************************************************************
52  OBSERVATION TYPE: CObservation2DRangeScan
53  ********************************************************************/
54  const CObservation2DRangeScan* o =
55  static_cast<const CObservation2DRangeScan*>(obs);
56 
57  // Build a points-map representation of the points from the scan
58  // (coordinates are wrt the robot base)
59 
60  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
61  CPose3D sensorPose(UNINITIALIZED_POSE);
62  sensorPose.composeFrom(robotPose3D, o->sensorPose);
63  sensorPt =
64  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
65 
66  const CPointsMap* scanPts =
68  const size_t nPts = scanPts->size();
69 
70  // Transform 3D point cloud:
71  scan.reserve(nPts);
72 
74  for (size_t i = 0; i < nPts; i++)
75  {
76  // Load the next point:
77  scanPts->getPointFast(i, pt.x, pt.y, pt.z);
78 
79  // Translation:
80  double gx, gy, gz;
81  robotPose3D.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
82 
83  // Add to this map:
84  scan.push_back(gx, gy, gz);
85  }
86  return true;
87  }
88  else if (IS_CLASS(obs, CObservation3DRangeScan))
89  {
90  /********************************************************************
91  OBSERVATION TYPE: CObservation3DRangeScan
92  ********************************************************************/
93  const CObservation3DRangeScan* o =
94  static_cast<const CObservation3DRangeScan*>(obs);
95 
96  // Build a points-map representation of the points from the scan
97  // (coordinates are wrt the robot base)
98  if (!o->hasPoints3D) return false;
99 
100  // Sensor_pose = robot_pose (+) sensor_pose_on_robot
101  CPose3D sensorPose(UNINITIALIZED_POSE);
102  sensorPose.composeFrom(robotPose3D, o->sensorPose);
103  sensorPt =
104  octomap::point3d(sensorPose.x(), sensorPose.y(), sensorPose.z());
105 
106  o->load(); // Just to make sure the points are loaded from an external
107  // source, if that's the case...
108  const size_t sizeRangeScan = o->points3D_x.size();
109 
110  // Transform 3D point cloud:
111  scan.reserve(sizeRangeScan);
112 
113  // For quicker access to values as "float" instead of "doubles":
115  robotPose3D.getHomogeneousMatrix(H);
116  const float m00 = H.get_unsafe(0, 0);
117  const float m01 = H.get_unsafe(0, 1);
118  const float m02 = H.get_unsafe(0, 2);
119  const float m03 = H.get_unsafe(0, 3);
120  const float m10 = H.get_unsafe(1, 0);
121  const float m11 = H.get_unsafe(1, 1);
122  const float m12 = H.get_unsafe(1, 2);
123  const float m13 = H.get_unsafe(1, 3);
124  const float m20 = H.get_unsafe(2, 0);
125  const float m21 = H.get_unsafe(2, 1);
126  const float m22 = H.get_unsafe(2, 2);
127  const float m23 = H.get_unsafe(2, 3);
128 
130  for (size_t i = 0; i < sizeRangeScan; i++)
131  {
132  pt.x = o->points3D_x[i];
133  pt.y = o->points3D_y[i];
134  pt.z = o->points3D_z[i];
135 
136  // Valid point?
137  if (pt.x != 0 || pt.y != 0 || pt.z != 0)
138  {
139  // Translation:
140  const float gx = m00 * pt.x + m01 * pt.y + m02 * pt.z + m03;
141  const float gy = m10 * pt.x + m11 * pt.y + m12 * pt.z + m13;
142  const float gz = m20 * pt.x + m21 * pt.y + m22 * pt.z + m23;
143 
144  // Add to this map:
145  scan.push_back(gx, gy, gz);
146  }
147  }
148  return true;
149  }
150 
151  return false;
152 }
153 
154 template <class OCTREE, class OCTREE_NODE>
156  const std::string& filNamePrefix) const
157 {
158  MRPT_START
159 
160  // Save as 3D Scene:
161  {
164  mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
165 
166  this->getAs3DObject(obj3D);
167 
168  scene.insert(obj3D);
169 
170  const std::string fil = filNamePrefix + std::string("_3D.3Dscene");
171  scene.saveToFile(fil);
172  }
173 
174  // Save as ".bt" file (a binary format from the octomap lib):
175  {
176  const std::string fil = filNamePrefix + std::string("_binary.bt");
177  m_impl->m_octomap.writeBinaryConst(fil);
178  }
179  MRPT_END
180 }
181 
182 template <class OCTREE, class OCTREE_NODE>
184  const mrpt::obs::CObservation* obs, const mrpt::poses::CPose3D& takenFrom)
185 {
186  octomap::point3d sensorPt;
187  octomap::Pointcloud scan;
188 
189  if (!internal_build_PointCloud_for_observation(
190  obs, &takenFrom, sensorPt, scan))
191  return 0; // Nothing to do.
192 
193  octomap::OcTreeKey key;
194  const size_t N = scan.size();
195 
196  double log_lik = 0;
197  for (size_t i = 0; i < N; i += likelihoodOptions.decimation)
198  {
199  if (m_impl->m_octomap
200  .coordToKeyChecked(scan.getPoint(i), key))
201  {
202  OCTREE_NODE* node =
203  m_impl->m_octomap.search(key, 0 /*depth*/);
204  if (node) log_lik += std::log(node->getOccupancy());
205  }
206  }
207 
208  return log_lik;
209 }
210 
211 template <class OCTREE, class OCTREE_NODE>
213  const float x, const float y, const float z, double& prob_occupancy) const
214 {
215  octomap::OcTreeKey key;
216  if (m_impl->m_octomap
217  .coordToKeyChecked(octomap::point3d(x, y, z), key))
218  {
219  OCTREE_NODE* node =
220  m_impl->m_octomap.search(key, 0 /*depth*/);
221  if (!node) return false;
222 
223  prob_occupancy = node->getOccupancy();
224  return true;
225  }
226  else
227  return false;
228 }
229 
230 template <class OCTREE, class OCTREE_NODE>
232  const CPointsMap& ptMap, const float sensor_x, const float sensor_y,
233  const float sensor_z)
234 {
235  MRPT_START
236  const octomap::point3d sensorPt(sensor_x, sensor_y, sensor_z);
237  size_t N;
238  const float *xs, *ys, *zs;
239  ptMap.getPointsBuffer(N, xs, ys, zs);
240  for (size_t i = 0; i < N; i++)
241  m_impl->m_octomap
242  .insertRay(
243  sensorPt, octomap::point3d(xs[i], ys[i], zs[i]),
244  insertionOptions.maxrange, insertionOptions.pruning);
245  MRPT_END
246 }
247 
248 template <class OCTREE, class OCTREE_NODE>
250  const mrpt::math::TPoint3D& origin, const mrpt::math::TPoint3D& direction,
251  mrpt::math::TPoint3D& end, bool ignoreUnknownCells, double maxRange) const
252 {
253  octomap::point3d _end;
254 
255  const bool ret =
256  m_impl->m_octomap
257  .castRay(
258  octomap::point3d(origin.x, origin.y, origin.z),
259  octomap::point3d(direction.x, direction.y, direction.z), _end,
260  ignoreUnknownCells, maxRange);
261 
262  end.x = _end.x();
263  end.y = _end.y();
264  end.z = _end.z();
265  return ret;
266 }
267 
268 /*---------------------------------------------------------------
269  TInsertionOptions
270  ---------------------------------------------------------------*/
271 template <class OCTREE, class OCTREE_NODE>
274  : maxrange(-1.),
275  pruning(true),
276  m_parent(&parent),
277  // Default values from octomap:
278  occupancyThres(0.5),
279  probHit(0.7),
280  probMiss(0.4),
281  clampingThresMin(0.1192),
282  clampingThresMax(0.971)
283 {
284 }
285 
286 template <class OCTREE, class OCTREE_NODE>
288  : maxrange(-1.),
289  pruning(true),
290  m_parent(nullptr),
291  // Default values from octomap:
292  occupancyThres(0.5),
293  probHit(0.7),
294  probMiss(0.4),
295  clampingThresMin(0.1192),
296  clampingThresMax(0.971)
297 {
298 }
299 
300 template <class OCTREE, class OCTREE_NODE>
302  : decimation(1)
303 {
304 }
305 
306 template <class OCTREE, class OCTREE_NODE>
309 {
310  const int8_t version = 0;
311  out << version;
312  out << decimation;
313 }
314 
315 template <class OCTREE, class OCTREE_NODE>
318 {
319  int8_t version;
320  in >> version;
321  switch (version)
322  {
323  case 0:
324  {
325  in >> decimation;
326  }
327  break;
328  default:
330  }
331 }
332 
333 template <class OCTREE, class OCTREE_NODE>
335  std::ostream& out) const
336 {
337  out << mrpt::format(
338  "\n----------- [COctoMapBase<>::TInsertionOptions] ------------ \n\n");
339 
340  LOADABLEOPTS_DUMP_VAR(maxrange, double);
341  LOADABLEOPTS_DUMP_VAR(pruning, bool);
342 
348 
349  out << mrpt::format("\n");
350 }
351 
352 template <class OCTREE, class OCTREE_NODE>
354  std::ostream& out) const
355 {
356  out << mrpt::format(
357  "\n----------- [COctoMapBase<>::TLikelihoodOptions] ------------ \n\n");
358 
359  LOADABLEOPTS_DUMP_VAR(decimation, int);
360 }
361 
362 /*---------------------------------------------------------------
363  loadFromConfigFile
364  ---------------------------------------------------------------*/
365 template <class OCTREE, class OCTREE_NODE>
367  const mrpt::config::CConfigFileBase& iniFile, const std::string& section)
368 {
369  MRPT_LOAD_CONFIG_VAR(maxrange, double, iniFile, section);
370  MRPT_LOAD_CONFIG_VAR(pruning, bool, iniFile, section);
371 
372  MRPT_LOAD_CONFIG_VAR(occupancyThres, double, iniFile, section);
373  MRPT_LOAD_CONFIG_VAR(probHit, double, iniFile, section);
374  MRPT_LOAD_CONFIG_VAR(probMiss, double, iniFile, section);
375  MRPT_LOAD_CONFIG_VAR(clampingThresMin, double, iniFile, section);
376  MRPT_LOAD_CONFIG_VAR(clampingThresMax, double, iniFile, section);
377 
378  // Set loaded options into the actual octomap object, if any:
379  this->setOccupancyThres(occupancyThres);
380  this->setProbHit(probHit);
381  this->setProbMiss(probMiss);
382  this->setClampingThresMin(clampingThresMin);
383  this->setClampingThresMax(clampingThresMax);
384 }
385 
386 template <class OCTREE, class OCTREE_NODE>
388  const mrpt::config::CConfigFileBase& iniFile, const std::string& section)
389 {
390  MRPT_LOAD_CONFIG_VAR(decimation, int, iniFile, section);
391 }
392 
393 /* COctoMapColoured */
394 template <class OCTREE, class OCTREE_NODE>
397 {
398  const int8_t version = 0;
399  out << version;
400  out << generateGridLines << generateOccupiedVoxels << visibleOccupiedVoxels
401  << generateFreeVoxels << visibleFreeVoxels;
402 }
403 
404 template <class OCTREE, class OCTREE_NODE>
407 {
408  int8_t version;
409  in >> version;
410  switch (version)
411  {
412  case 0:
413  {
414  in >> generateGridLines >> generateOccupiedVoxels >>
415  visibleOccupiedVoxels >> generateFreeVoxels >>
416  visibleFreeVoxels;
417  }
418  break;
419  default:
421  }
422 }
423 
424 }
425 
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:140
virtual void setProbMiss(double prob)=0
virtual double getOccupancyThres() const =0
#define MRPT_START
Definition: exceptions.h:262
virtual double getClampingThresMin() const =0
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...
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.
virtual void setProbHit(double prob)=0
virtual double getClampingThresMax() const =0
signed char int8_t
Definition: rptypes.h:40
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
#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
virtual void setClampingThresMin(double thresProb)=0
TLikelihoodOptions()
Initilization of default parameters.
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
A numeric matrix of compile-time fixed size.
This class allows loading and storing values and vectors of different types from a configuration text...
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
GLuint GLuint end
Definition: glext.h:3528
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
This namespace contains representation of robot actions and observations.
string iniFile(myDataDir+string("benchmark-options.ini"))
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
COctoMapBase(double resolution)
Constructor, defines the resolution of the octomap (length of each voxel side)
double x
X,Y,Z coordinates.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
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...
bool saveToFile(const std::string &fil) const
Saves the scene to a 3Dscene file, loadable by the application SceneViewer3D.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
#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...
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
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:245
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
virtual double getProbMiss() const =0
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
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
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
#define MRPT_END
Definition: exceptions.h:266
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:59
virtual void setOccupancyThres(double prob)=0
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
GLenum GLint GLint y
Definition: glext.h:3538
virtual double getProbHit() const =0
GLenum GLint x
Definition: glext.h:3538
Lightweight 3D point.
virtual void setClampingThresMax(double thresProb)=0
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:408
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 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