MRPT  1.9.9
COctoMapBase.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
13 #include <mrpt/core/pimpl.h>
15 #include <mrpt/maps/CMetricMap.h>
16 #include <mrpt/obs/obs_frwds.h>
19 
20 namespace mrpt::maps
21 {
22 /** A three-dimensional probabilistic occupancy grid, implemented as an
23  * octo-tree with the "octomap" C++ library.
24  * This base class represents a 3D map where each voxel may contain an
25  * "occupancy" property, RGBD data, etc. depending on the derived class.
26  *
27  * As with any other mrpt::maps::CMetricMap, you can obtain a 3D representation
28  * of the map calling getAs3DObject() or getAsOctoMapVoxels()
29  *
30  * To use octomap's iterators to go through the voxels, use
31  * COctoMap::getOctomap()
32  *
33  * The octomap library was presented in:
34  * - K. M. Wurm, A. Hornung, M. Bennewitz, C. Stachniss, and W. Burgard,
35  * <i>"OctoMap: A Probabilistic, Flexible, and Compact 3D Map Representation
36  * for Robotic Systems"</i>
37  * in Proc. of the ICRA 2010 Workshop on Best Practice in 3D Perception and
38  * Modeling for Mobile Manipulation, 2010. Software available at
39  * http://octomap.sf.net/.
40  *
41  * \sa CMetricMap, the example in "MRPT/samples/octomap_simple"
42  * \ingroup mrpt_maps_grp
43  */
44 template <class octree_t, class octree_node_t>
46 {
47  public:
49 
50  /** Constructor, defines the resolution of the octomap (length of each voxel
51  * side) */
52  COctoMapBase(double resolution);
53  ~COctoMapBase() override = default;
54  /** Get a reference to the internal octomap object. Example:
55  * \code
56  * mrpt::maps::COctoMap map;
57  * octomap::OcTree &om = map.getOctomap<octomap::OcTree>();
58  * \endcode
59  */
60  template <class OCTOMAP_CLASS>
61  inline OCTOMAP_CLASS& getOctomap()
62  {
63  return m_impl->m_octomap;
64  }
65 
66  /** With this struct options are provided to the observation insertion
67  * process.
68  * \sa CObservation::insertObservationInto()
69  */
71  {
72  /** Initilization of default parameters */
73  TInsertionOptions(myself_t& parent);
74 
75  TInsertionOptions(); //!< Especial constructor, not attached to a real
76  //! COctoMap object: used only in limited
77  //! situations, since get*() methods don't work,
78  //! etc.
80  {
81  // Copy all but the m_parent pointer!
82  maxrange = o.maxrange;
83  pruning = o.pruning;
84  const bool o_has_parent = o.m_parent.get() != nullptr;
86  o_has_parent ? o.getOccupancyThres() : o.occupancyThres);
87  setProbHit(o_has_parent ? o.getProbHit() : o.probHit);
88  setProbMiss(o_has_parent ? o.getProbMiss() : o.probMiss);
90  o_has_parent ? o.getClampingThresMin() : o.clampingThresMin);
92  o_has_parent ? o.getClampingThresMax() : o.clampingThresMax);
93  return *this;
94  }
95 
96  void loadFromConfigFile(
98  const std::string& section) override; // See base docs
99  void dumpToTextStream(
100  std::ostream& out) const override; // See base docs
101 
102  double maxrange{
103  -1.}; //!< maximum range for how long individual beams are
104  //! inserted (default -1: complete beam)
105  bool pruning{true}; //!< 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{0.5}; // sets the threshold for occupancy (sensor
210  // model) (Default=0.5)
211  double probHit{
212  0.7}; // sets the probablility for a "hit" (will be converted
213  // to logodds) - sensor model (Default=0.7)
214  double probMiss{0.4}; // sets the probablility for a "miss" (will be
215  // converted to logodds) - sensor model (Default=0.4)
217  0.1192}; // sets the minimum threshold for occupancy
218  // clamping (sensor model) (Default=0.1192, -2
219  // in log odds)
221  0.971}; // sets the maximum threshold for occupancy
222  // clamping (sensor model) (Default=0.971, 3.5
223  // in log odds)
224  };
225 
226  TInsertionOptions insertionOptions; //!< The options used when inserting
227  //! observations in the map
228 
229  /** Options used when evaluating "computeObservationLikelihood"
230  * \sa CObservation::computeObservationLikelihood
231  */
233  {
234  /** Initilization of default parameters
235  */
237  ~TLikelihoodOptions() override = default;
238  void loadFromConfigFile(
240  const std::string& section) override; // See base docs
241  void dumpToTextStream(
242  std::ostream& out) const override; // See base docs
243 
244  /** Binary dump to stream */
246  /** Binary dump to stream */
248 
249  uint32_t decimation{1}; //!< Speed up the likelihood computation by
250  //! considering only one out of N rays (default=1)
251  };
252 
253  TLikelihoodOptions likelihoodOptions;
254 
256  const std::string& filNamePrefix) const override;
257 
258  /** Options for the conversion of a mrpt::maps::COctoMap into a
259  * mrpt::opengl::COctoMapVoxels */
261  {
263  false}; //!< Generate grid lines for all octree nodes,
264  //! useful to draw the "structure" of the
265  //! octree, but computationally costly (Default:
266  //! false)
267 
269  true}; //!< Generate voxels for the occupied
270  //! volumes (Default=true)
272  true}; //!< Set occupied voxels visible (requires
273  //! generateOccupiedVoxels=true)
274  //!(Default=true)
275 
276  bool generateFreeVoxels{true}; //!< Generate voxels for the freespace
277  //!(Default=true)
278  bool visibleFreeVoxels{true}; //!< Set free voxels visible (requires
279  //! generateFreeVoxels=true) (Default=true)
280 
281  TRenderingOptions() = default;
282 
283  /** Binary dump to stream */
285  /** Binary dump to stream */
287  };
288 
289  TRenderingOptions renderingOptions;
290 
291  /** Returns a 3D object representing the map.
292  * \sa renderingOptions
293  */
294  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override
295  {
296  auto gl_obj = mrpt::opengl::COctoMapVoxels::Create();
297  this->getAsOctoMapVoxels(*gl_obj);
298  outObj->insert(gl_obj);
299  }
300 
301  /** Builds a renderizable representation of the octomap as a
302  * mrpt::opengl::COctoMapVoxels object.
303  * \sa renderingOptions
304  */
305  virtual void getAsOctoMapVoxels(
306  mrpt::opengl::COctoMapVoxels& gl_obj) const = 0;
307 
308  /** Get the occupancy probability [0,1] of a point
309  * \return false if the point is not mapped, in which case the returned
310  * "prob" is undefined. */
311  bool getPointOccupancy(
312  const float x, const float y, const float z,
313  double& prob_occupancy) const;
314 
315  /** Update the octomap with a 2D or 3D scan, given directly as a point cloud
316  * and the 3D location of the sensor (the origin of the rays) in this map's
317  * frame of reference.
318  * Insertion parameters can be found in \a insertionOptions.
319  * \sa The generic observation insertion method
320  * CMetricMap::insertObservation()
321  */
322  void insertPointCloud(
323  const CPointsMap& ptMap, const float sensor_x, const float sensor_y,
324  const float sensor_z);
325 
326  /** Performs raycasting in 3d, similar to computeRay().
327  *
328  * A ray is cast from origin with a given direction, the first occupied
329  * cell is returned (as center coordinate). If the starting coordinate is
330  * already
331  * occupied in the tree, this coordinate will be returned as a hit.
332  *
333  * @param origin starting coordinate of ray
334  * @param direction A vector pointing in the direction of the raycast. Does
335  * not need to be normalized.
336  * @param end returns the center of the cell that was hit by the ray, if
337  * successful
338  * @param ignoreUnknownCells whether unknown cells are ignored. If false
339  * (default), the raycast aborts when an unkown cell is hit.
340  * @param maxRange Maximum range after which the raycast is aborted (<= 0:
341  * no limit, default)
342  * @return whether or not an occupied cell was hit
343  */
344  bool castRay(
345  const mrpt::math::TPoint3D& origin,
346  const mrpt::math::TPoint3D& direction, mrpt::math::TPoint3D& end,
347  bool ignoreUnknownCells = false, double maxRange = -1.0) const;
348 
349  virtual void setOccupancyThres(double prob) = 0;
350  virtual void setProbHit(double prob) = 0;
351  virtual void setProbMiss(double prob) = 0;
352  virtual void setClampingThresMin(double thresProb) = 0;
353  virtual void setClampingThresMax(double thresProb) = 0;
354  virtual double getOccupancyThres() const = 0;
355  virtual float getOccupancyThresLog() const = 0;
356  virtual double getProbHit() const = 0;
357  virtual float getProbHitLog() const = 0;
358  virtual double getProbMiss() const = 0;
359  virtual float getProbMissLog() const = 0;
360  virtual double getClampingThresMin() const = 0;
361  virtual float getClampingThresMinLog() const = 0;
362  virtual double getClampingThresMax() const = 0;
363  virtual float getClampingThresMaxLog() const = 0;
364 
365  protected:
366  /** Builds the list of 3D points in global coordinates for a generic
367  * observation. Used for both, insertObservation() and computeLikelihood().
368  * \param[out] point3d_sensorPt Is a pointer to a "point3D".
369  * \param[out] ptr_scan Is in fact a pointer to "octomap::Pointcloud". Not
370  * declared as such to avoid headers dependencies in user code.
371  * \return false if the observation kind is not applicable.
372  */
373  template <class octomap_point3d, class octomap_pointcloud>
375  const mrpt::obs::CObservation& obs,
376  const mrpt::poses::CPose3D* robotPose, octomap_point3d& sensorPt,
377  octomap_pointcloud& scan) const;
378 
379  struct Impl;
380 
382 
383  private:
384  // See docs in base class
386  const mrpt::obs::CObservation& obs,
387  const mrpt::poses::CPose3D& takenFrom) override;
388 
389 }; // End of class def.
390 } // namespace mrpt::maps
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Definition: COctoMapBase.h:294
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
Options for the conversion of a mrpt::maps::COctoMap into a mrpt::opengl::COctoMapVoxels.
Definition: COctoMapBase.h:260
virtual void setProbMiss(double prob)=0
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:249
bool generateGridLines
Generate grid lines for all octree nodes,.
Definition: COctoMapBase.h:262
virtual double getOccupancyThres() const =0
virtual double getClampingThresMin() const =0
GLdouble GLdouble z
Definition: glext.h:3879
TRenderingOptions renderingOptions
Definition: COctoMapBase.h:289
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
TRenderingOptions()=default
generateFreeVoxels=true) (Default=true)
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:268
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:79
double maxrange
maximum range for how long individual beams are
Definition: COctoMapBase.h:102
TInsertionOptions insertionOptions
The options used when inserting.
Definition: COctoMapBase.h:226
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:45
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:379
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:65
This class allows loading and storing values and vectors of different types from a configuration text...
TLikelihoodOptions likelihoodOptions
Definition: COctoMapBase.h:253
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:61
bool visibleOccupiedVoxels
volumes (Default=true)
Definition: COctoMapBase.h:271
GLuint GLuint end
Definition: glext.h:3532
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)
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.
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:4116
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
~COctoMapBase() override=default
virtual float getClampingThresMaxLog() const =0
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:53
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:84
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:7391
GLsizei GLsizei GLchar * source
Definition: glext.h:4097
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:3542
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
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
virtual double getProbHit() const =0
virtual float getOccupancyThresLog() const =0
With this struct options are provided to the observation insertion process.
Definition: COctoMapBase.h:70
bool generateFreeVoxels
generateOccupiedVoxels=true) (Default=true)
Definition: COctoMapBase.h:276
GLenum GLint x
Definition: glext.h:3542
Lightweight 3D point.
Definition: TPoint3D.h:90
virtual void setClampingThresMax(double thresProb)=0
unsigned __int32 uint32_t
Definition: rptypes.h:50
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: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019