MRPT  1.9.9
COctoMapBase.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 #ifndef MRPT_COctoMapBase_H
11 #define MRPT_COctoMapBase_H
12 
13 #include <mrpt/maps/CMetricMap.h>
18 #include <mrpt/obs/obs_frwds.h>
19 #include <mrpt/core/pimpl.h>
20 
21 namespace mrpt::maps
22 {
23 /** A three-dimensional probabilistic occupancy grid, implemented as an
24  * octo-tree with the "octomap" C++ library.
25  * This base class represents a 3D map where each voxel may contain an
26  * "occupancy" property, RGBD data, etc. depending on the derived class.
27  *
28  * As with any other mrpt::maps::CMetricMap, you can obtain a 3D representation
29  * of the map calling getAs3DObject() or getAsOctoMapVoxels()
30  *
31  * To use octomap's iterators to go through the voxels, use
32  * COctoMap::getOctomap()
33  *
34  * The octomap library was presented in:
35  * - K. M. Wurm, A. Hornung, M. Bennewitz, C. Stachniss, and W. Burgard,
36  * <i>"OctoMap: A Probabilistic, Flexible, and Compact 3D Map Representation
37  * for Robotic Systems"</i>
38  * in Proc. of the ICRA 2010 Workshop on Best Practice in 3D Perception and
39  * Modeling for Mobile Manipulation, 2010. Software available at
40  * http://octomap.sf.net/.
41  *
42  * \sa CMetricMap, the example in "MRPT/samples/octomap_simple"
43  * \ingroup mrpt_maps_grp
44  */
45 template <class octree_t, class octree_node_t>
47 {
48  public:
50 
51  /** Constructor, defines the resolution of the octomap (length of each voxel
52  * side) */
53  COctoMapBase(double resolution);
54  virtual ~COctoMapBase() {}
55  /** Get a reference to the internal octomap object. Example:
56  * \code
57  * mrpt::maps::COctoMap map;
58  * octomap::OcTree &om = map.getOctomap<octomap::OcTree>();
59  * \endcode
60  */
61  template <class OCTOMAP_CLASS>
62  inline OCTOMAP_CLASS& getOctomap()
63  {
64  return m_impl->m_octomap;
65  }
66 
67  /** With this struct options are provided to the observation insertion
68  * process.
69  * \sa CObservation::insertObservationInto()
70  */
72  {
73  /** Initilization of default parameters */
74  TInsertionOptions(myself_t& parent);
75 
76  TInsertionOptions(); //!< Especial constructor, not attached to a real
77  //! COctoMap object: used only in limited
78  //! situations, since get*() methods don't work,
79  //! etc.
81  {
82  // Copy all but the m_parent pointer!
83  maxrange = o.maxrange;
84  pruning = o.pruning;
85  const bool o_has_parent = o.m_parent.get() != NULL;
87  o_has_parent ? o.getOccupancyThres() : o.occupancyThres);
88  setProbHit(o_has_parent ? o.getProbHit() : o.probHit);
89  setProbMiss(o_has_parent ? o.getProbMiss() : o.probMiss);
91  o_has_parent ? o.getClampingThresMin() : o.clampingThresMin);
93  o_has_parent ? o.getClampingThresMax() : o.clampingThresMax);
94  return *this;
95  }
96 
97  void loadFromConfigFile(
99  const std::string& section) override; // See base docs
100  void dumpToTextStream(
101  std::ostream& out) const override; // See base docs
102 
103  double maxrange; //!< maximum range for how long individual beams are
104  //! inserted (default -1: complete beam)
105  bool pruning; //!< whether the tree is (losslessly) pruned after
106  //! insertion (default: true)
107 
108  /// (key name in .ini files: "occupancyThres") sets the threshold for
109  /// occupancy (sensor model) (Default=0.5)
110  void setOccupancyThres(double prob)
111  {
112  if (m_parent.get()) m_parent->setOccupancyThres(prob);
113  }
114  /// (key name in .ini files: "probHit")sets the probablility for a "hit"
115  /// (will be converted to logodds) - sensor model (Default=0.7)
116  void setProbHit(double prob)
117  {
118  if (m_parent.get()) m_parent->setProbHit(prob);
119  }
120  /// (key name in .ini files: "probMiss")sets the probablility for a
121  /// "miss" (will be converted to logodds) - sensor model (Default=0.4)
122  void setProbMiss(double prob)
123  {
124  if (m_parent.get()) m_parent->setProbMiss(prob);
125  }
126  /// (key name in .ini files: "clampingThresMin")sets the minimum
127  /// threshold for occupancy clamping (sensor model) (Default=0.1192, -2
128  /// in log odds)
129  void setClampingThresMin(double thresProb)
130  {
131  if (m_parent.get()) m_parent->setClampingThresMin(thresProb);
132  }
133  /// (key name in .ini files: "clampingThresMax")sets the maximum
134  /// threshold for occupancy clamping (sensor model) (Default=0.971, 3.5
135  /// in log odds)
136  void setClampingThresMax(double thresProb)
137  {
138  if (m_parent.get()) m_parent->setClampingThresMax(thresProb);
139  }
140 
141  /// @return threshold (probability) for occupancy - sensor model
142  double getOccupancyThres() const
143  {
144  if (m_parent.get())
145  return m_parent->getOccupancyThres();
146  else
147  return this->occupancyThres;
148  }
149  /// @return threshold (logodds) for occupancy - sensor model
150  float getOccupancyThresLog() const
151  {
152  return m_parent->getOccupancyThresLog();
153  }
154 
155  /// @return probablility for a "hit" in the sensor model (probability)
156  double getProbHit() const
157  {
158  if (m_parent.get())
159  return m_parent->getProbHit();
160  else
161  return this->probHit;
162  }
163  /// @return probablility for a "hit" in the sensor model (logodds)
164  float getProbHitLog() const { return m_parent->getProbHitLog(); }
165  /// @return probablility for a "miss" in the sensor model (probability)
166  double getProbMiss() const
167  {
168  if (m_parent.get())
169  return m_parent->getProbMiss();
170  else
171  return this->probMiss;
172  }
173  /// @return probablility for a "miss" in the sensor model (logodds)
174  float getProbMissLog() const { return m_parent->getProbMissLog(); }
175  /// @return minimum threshold for occupancy clamping in the sensor model
176  /// (probability)
177  double getClampingThresMin() const
178  {
179  if (m_parent.get())
180  return m_parent->getClampingThresMin();
181  else
182  return this->clampingThresMin;
183  }
184  /// @return minimum threshold for occupancy clamping in the sensor model
185  /// (logodds)
187  {
188  return m_parent->getClampingThresMinLog();
189  }
190  /// @return maximum threshold for occupancy clamping in the sensor model
191  /// (probability)
192  double getClampingThresMax() const
193  {
194  if (m_parent.get())
195  return m_parent->getClampingThresMax();
196  else
197  return this->clampingThresMax;
198  }
199  /// @return maximum threshold for occupancy clamping in the sensor model
200  /// (logodds)
202  {
203  return m_parent->getClampingThresMaxLog();
204  }
205 
206  private:
208 
209  double occupancyThres; // sets the threshold for occupancy (sensor
210  // model) (Default=0.5)
211  double probHit; // sets the probablility for a "hit" (will be converted
212  // to logodds) - sensor model (Default=0.7)
213  double probMiss; // sets the probablility for a "miss" (will be
214  // converted to logodds) - sensor model (Default=0.4)
215  double clampingThresMin; // sets the minimum threshold for occupancy
216  // clamping (sensor model) (Default=0.1192, -2
217  // in log odds)
218  double clampingThresMax; // sets the maximum threshold for occupancy
219  // clamping (sensor model) (Default=0.971, 3.5
220  // in log odds)
221  };
222 
223  TInsertionOptions insertionOptions; //!< The options used when inserting
224  //! observations in the map
225 
226  /** Options used when evaluating "computeObservationLikelihood"
227  * \sa CObservation::computeObservationLikelihood
228  */
230  {
231  /** Initilization of default parameters
232  */
234  virtual ~TLikelihoodOptions() {}
235  void loadFromConfigFile(
237  const std::string& section) override; // See base docs
238  void dumpToTextStream(
239  std::ostream& out) const override; // See base docs
240 
241  /** Binary dump to stream */
243  /** Binary dump to stream */
245 
246  uint32_t decimation; //!< Speed up the likelihood computation by
247  //! considering only one out of N rays (default=1)
248  };
249 
250  TLikelihoodOptions likelihoodOptions;
251 
253  const std::string& filNamePrefix) const override;
254 
255  /** Options for the conversion of a mrpt::maps::COctoMap into a
256  * mrpt::opengl::COctoMapVoxels */
258  {
259  bool generateGridLines; //!< Generate grid lines for all octree nodes,
260  //! useful to draw the "structure" of the
261  //! octree, but computationally costly (Default:
262  //! false)
263 
264  bool generateOccupiedVoxels; //!< Generate voxels for the occupied
265  //! volumes (Default=true)
266  bool visibleOccupiedVoxels; //!< Set occupied voxels visible (requires
267  //! generateOccupiedVoxels=true)
268  //!(Default=true)
269 
270  bool generateFreeVoxels; //!< Generate voxels for the freespace
271  //!(Default=true)
272  bool visibleFreeVoxels; //!< Set free voxels visible (requires
273  //! generateFreeVoxels=true) (Default=true)
274 
276  : generateGridLines(false),
278  visibleOccupiedVoxels(true),
279  generateFreeVoxels(true),
280  visibleFreeVoxels(true)
281  {
282  }
283 
284  /** Binary dump to stream */
286  /** Binary dump to stream */
288  };
289 
290  TRenderingOptions renderingOptions;
291 
292  /** Returns a 3D object representing the map.
293  * \sa renderingOptions
294  */
295  virtual void getAs3DObject(
296  mrpt::opengl::CSetOfObjects::Ptr& outObj) const override
297  {
298  auto gl_obj = mrpt::opengl::COctoMapVoxels::Create();
299  this->getAsOctoMapVoxels(*gl_obj);
300  outObj->insert(gl_obj);
301  }
302 
303  /** Builds a renderizable representation of the octomap as a
304  * mrpt::opengl::COctoMapVoxels object.
305  * \sa renderingOptions
306  */
307  virtual void getAsOctoMapVoxels(
308  mrpt::opengl::COctoMapVoxels& gl_obj) const = 0;
309 
310  /** Get the occupancy probability [0,1] of a point
311  * \return false if the point is not mapped, in which case the returned
312  * "prob" is undefined. */
313  bool getPointOccupancy(
314  const float x, const float y, const float z,
315  double& prob_occupancy) const;
316 
317  /** Update the octomap with a 2D or 3D scan, given directly as a point cloud
318  * and the 3D location of the sensor (the origin of the rays) in this map's
319  * frame of reference.
320  * Insertion parameters can be found in \a insertionOptions.
321  * \sa The generic observation insertion method
322  * CMetricMap::insertObservation()
323  */
324  void insertPointCloud(
325  const CPointsMap& ptMap, const float sensor_x, const float sensor_y,
326  const float sensor_z);
327 
328  /** Performs raycasting in 3d, similar to computeRay().
329  *
330  * A ray is cast from origin with a given direction, the first occupied
331  * cell is returned (as center coordinate). If the starting coordinate is
332  * already
333  * occupied in the tree, this coordinate will be returned as a hit.
334  *
335  * @param origin starting coordinate of ray
336  * @param direction A vector pointing in the direction of the raycast. Does
337  * not need to be normalized.
338  * @param end returns the center of the cell that was hit by the ray, if
339  * successful
340  * @param ignoreUnknownCells whether unknown cells are ignored. If false
341  * (default), the raycast aborts when an unkown cell is hit.
342  * @param maxRange Maximum range after which the raycast is aborted (<= 0:
343  * no limit, default)
344  * @return whether or not an occupied cell was hit
345  */
346  bool castRay(
347  const mrpt::math::TPoint3D& origin,
348  const mrpt::math::TPoint3D& direction, mrpt::math::TPoint3D& end,
349  bool ignoreUnknownCells = false, double maxRange = -1.0) const;
350 
351  virtual void setOccupancyThres(double prob) = 0;
352  virtual void setProbHit(double prob) = 0;
353  virtual void setProbMiss(double prob) = 0;
354  virtual void setClampingThresMin(double thresProb) = 0;
355  virtual void setClampingThresMax(double thresProb) = 0;
356  virtual double getOccupancyThres() const = 0;
357  virtual float getOccupancyThresLog() const = 0;
358  virtual double getProbHit() const = 0;
359  virtual float getProbHitLog() const = 0;
360  virtual double getProbMiss() const = 0;
361  virtual float getProbMissLog() const = 0;
362  virtual double getClampingThresMin() const = 0;
363  virtual float getClampingThresMinLog() const = 0;
364  virtual double getClampingThresMax() const = 0;
365  virtual float getClampingThresMaxLog() const = 0;
366 
367  protected:
368  /** Builds the list of 3D points in global coordinates for a generic
369  * observation. Used for both, insertObservation() and computeLikelihood().
370  * \param[out] point3d_sensorPt Is a pointer to a "point3D".
371  * \param[out] ptr_scan Is in fact a pointer to "octomap::Pointcloud". Not
372  * declared as such to avoid headers dependencies in user code.
373  * \return false if the observation kind is not applicable.
374  */
375  template <class octomap_point3d, class octomap_pointcloud>
377  const mrpt::obs::CObservation* obs,
378  const mrpt::poses::CPose3D* robotPose, octomap_point3d& sensorPt,
379  octomap_pointcloud& scan) const;
380 
381  struct Impl;
382 
384 
385  private:
386  // See docs in base class
388  const mrpt::obs::CObservation* obs,
389  const mrpt::poses::CPose3D& takenFrom) override;
390 
391 }; // End of class def.
392 }
393 #endif
394 
395 
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()
Options for the conversion of a mrpt::maps::COctoMap into a mrpt::opengl::COctoMapVoxels.
Definition: COctoMapBase.h:257
virtual void setProbMiss(double prob)=0
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
uint32_t decimation
Speed up the likelihood computation by.
Definition: COctoMapBase.h:246
virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Definition: COctoMapBase.h:295
bool generateGridLines
Generate grid lines for all octree nodes,.
Definition: COctoMapBase.h:259
virtual double getOccupancyThres() const =0
virtual double getClampingThresMin() const =0
GLdouble GLdouble z
Definition: glext.h:3872
TRenderingOptions renderingOptions
Definition: COctoMapBase.h:290
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
spimpl::impl_ptr< T > pimpl
Definition: pimpl.h:15
void setClampingThresMax(double thresProb)
(key name in .ini files: "clampingThresMax")sets the maximum threshold for occupancy clamping (sensor...
Definition: COctoMapBase.h:136
void setClampingThresMin(double thresProb)
(key name in .ini files: "clampingThresMin")sets the minimum threshold for occupancy clamping (sensor...
Definition: COctoMapBase.h:129
virtual void setProbHit(double prob)=0
virtual double getClampingThresMax() const =0
void setOccupancyThres(double prob)
insertion (default: true)
Definition: COctoMapBase.h:110
bool generateOccupiedVoxels
useful to draw the "structure" of the octree, but computationally costly (Default: false) ...
Definition: COctoMapBase.h:264
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
virtual float getProbHitLog() const =0
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
TInsertionOptions & operator=(const TInsertionOptions &o)
COctoMap object: used only in limited situations, since get*() methods don&#39;t work, etc.
Definition: COctoMapBase.h:80
double maxrange
maximum range for how long individual beams are
Definition: COctoMapBase.h:103
TInsertionOptions insertionOptions
The options used when inserting.
Definition: COctoMapBase.h:223
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).
virtual void setClampingThresMin(double thresProb)=0
mrpt::pimpl< Impl > m_impl
Definition: COctoMapBase.h:381
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
This class allows loading and storing values and vectors of different types from a configuration text...
TLikelihoodOptions likelihoodOptions
Definition: COctoMapBase.h:250
A wrapper class for pointers whose copy operations from other objects of the same type are ignored...
OCTOMAP_CLASS & getOctomap()
Get a reference to the internal octomap object.
Definition: COctoMapBase.h:62
TRenderingOptions()
generateFreeVoxels=true) (Default=true)
Definition: COctoMapBase.h:275
bool visibleOccupiedVoxels
volumes (Default=true)
Definition: COctoMapBase.h:266
GLuint GLuint end
Definition: glext.h:3528
bool internal_build_PointCloud_for_observation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose, octomap_point3d &sensorPt, octomap_pointcloud &scan) const
Builds the list of 3D points in global coordinates for a generic observation.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
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)
static Ptr Create(Args &&... args)
TInsertionOptions()
Especial constructor, not attached to a real.
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.
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().
bool pruning
inserted (default -1: complete beam)
Definition: COctoMapBase.h:105
virtual float getProbMissLog() const =0
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.
void setProbMiss(double prob)
(key name in .ini files: "probMiss")sets the probablility for a "miss" (will be converted to logodds)...
Definition: COctoMapBase.h:122
virtual float getClampingThresMaxLog() const =0
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:52
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
virtual double getProbMiss() const =0
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.
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
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
virtual void setOccupancyThres(double prob)=0
virtual float getClampingThresMinLog() const =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
void setProbHit(double prob)
(key name in .ini files: "probHit")sets the probablility for a "hit" (will be converted to logodds) -...
Definition: COctoMapBase.h:116
virtual double getProbHit() const =0
virtual float getOccupancyThresLog() const =0
With this struct options are provided to the observation insertion process.
Definition: COctoMapBase.h:71
bool generateFreeVoxels
generateOccupiedVoxels=true) (Default=true)
Definition: COctoMapBase.h:270
GLenum GLint x
Definition: glext.h:3538
Lightweight 3D point.
virtual void setClampingThresMax(double thresProb)=0
unsigned __int32 uint32_t
Definition: rptypes.h:47
mrpt::ignored_copy_ptr< myself_t > m_parent
Definition: COctoMapBase.h:207
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const =0
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...



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