Main MRPT website > C++ reference
MRPT logo
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-2014, 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/slam/CMetricMap.h>
19 
20 #include <mrpt/maps/link_pragmas.h>
21 
22 namespace mrpt
23 {
24  namespace slam
25  {
26  class CPointsMap;
27  class CObservation2DRangeScan;
28  class CObservation3DRangeScan;
29 
30  /** A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library.
31  * This base class represents a 3D map where each voxel may contain an "occupancy" property, RGBD data, etc. depending on the derived class.
32  *
33  * As with any other mrpt::slam::CMetricMap, you can obtain a 3D representation of the map calling getAs3DObject() or getAsOctoMapVoxels()
34  *
35  * To use octomap's iterators to go through the voxels, use COctoMap::getOctomap()
36  *
37  * The octomap library was presented in:
38  * - K. M. Wurm, A. Hornung, M. Bennewitz, C. Stachniss, and W. Burgard,
39  * <i>"OctoMap: A Probabilistic, Flexible, and Compact 3D Map Representation for Robotic Systems"</i>
40  * in Proc. of the ICRA 2010 Workshop on Best Practice in 3D Perception and Modeling for Mobile Manipulation, 2010. Software available at 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,class OCTREE_NODE>
46  class COctoMapBase : public CMetricMap
47  {
48  public:
49  typedef COctoMapBase<OCTREE,OCTREE_NODE> myself_t; //!< The type of this MRPT class
50  typedef OCTREE octree_t; //!< The type of the octree class in the "octomap" library.
51  typedef OCTREE_NODE octree_node_t; //!< The type of nodes in the octree, in the "octomap" library.
52 
53 
54  /** Constructor, defines the resolution of the octomap (length of each voxel side) */
55  COctoMapBase(const double resolution=0.10) : insertionOptions(*this), m_octomap(resolution) { }
56  virtual ~COctoMapBase() { }
57 
58  /** Get a reference to the internal octomap object. Example:
59  * \code
60  * mrpt::maps::COctoMap map;
61  * ...
62  * octomap::OcTree &om = map.getOctomap();
63  *
64  *
65  * \endcode
66  */
67  inline OCTREE & getOctomap() { return m_octomap; }
68 
69  /** With this struct options are provided to the observation insertion process.
70  * \sa CObservation::insertObservationInto()
71  */
73  {
74  /** Initilization of default parameters */
75  TInsertionOptions( myself_t &parent );
76 
77  TInsertionOptions(); //!< Especial constructor, not attached to a real COctoMap object: used only in limited situations, since get*() methods don't work, etc.
79  {
80  // Copy all but the m_parent pointer!
81  maxrange = o.maxrange;
82  pruning = o.pruning;
83  const bool o_has_parent = o.m_parent.get()!=NULL;
84  setOccupancyThres( o_has_parent ? o.getOccupancyThres() : o.occupancyThres );
85  setProbHit( o_has_parent ? o.getProbHit() : o.probHit );
86  setProbMiss( o_has_parent ? o.getProbMiss() : o.probMiss );
89  return *this;
90  }
91 
92  /** See utils::CLoadableOptions */
93  void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string &section);
94  /** See utils::CLoadableOptions */
95  void dumpToTextStream(CStream &out) const;
96 
97  double maxrange; //!< maximum range for how long individual beams are inserted (default -1: complete beam)
98  bool pruning; //!< whether the tree is (losslessly) pruned after insertion (default: true)
99 
100  /// (key name in .ini files: "occupancyThres") sets the threshold for occupancy (sensor model) (Default=0.5)
101  void setOccupancyThres(double prob) { if(m_parent.get()) m_parent->m_octomap.setOccupancyThres(prob); }
102  /// (key name in .ini files: "probHit")sets the probablility for a "hit" (will be converted to logodds) - sensor model (Default=0.7)
103  void setProbHit(double prob) { if(m_parent.get()) m_parent->m_octomap.setProbHit(prob); }
104  /// (key name in .ini files: "probMiss")sets the probablility for a "miss" (will be converted to logodds) - sensor model (Default=0.4)
105  void setProbMiss(double prob) { if(m_parent.get()) m_parent->m_octomap.setProbMiss(prob); }
106  /// (key name in .ini files: "clampingThresMin")sets the minimum threshold for occupancy clamping (sensor model) (Default=0.1192, -2 in log odds)
107  void setClampingThresMin(double thresProb) { if(m_parent.get()) m_parent->m_octomap.setClampingThresMin(thresProb); }
108  /// (key name in .ini files: "clampingThresMax")sets the maximum threshold for occupancy clamping (sensor model) (Default=0.971, 3.5 in log odds)
109  void setClampingThresMax(double thresProb) { if(m_parent.get()) m_parent->m_octomap.setClampingThresMax(thresProb); }
110 
111  /// @return threshold (probability) for occupancy - sensor model
112  double getOccupancyThres() const { if(m_parent.get()) return m_parent->m_octomap.getOccupancyThres(); else return this->occupancyThres; }
113  /// @return threshold (logodds) for occupancy - sensor model
114  float getOccupancyThresLog() const { return m_parent->m_octomap.getOccupancyThresLog() ; }
115 
116  /// @return probablility for a "hit" in the sensor model (probability)
117  double getProbHit() const { if(m_parent.get()) return m_parent->m_octomap.getProbHit(); else return this->probHit; }
118  /// @return probablility for a "hit" in the sensor model (logodds)
119  float getProbHitLog() const { return m_parent->m_octomap.getProbHitLog(); }
120  /// @return probablility for a "miss" in the sensor model (probability)
121  double getProbMiss() const { if(m_parent.get()) return m_parent->m_octomap.getProbMiss(); else return this->probMiss; }
122  /// @return probablility for a "miss" in the sensor model (logodds)
123  float getProbMissLog() const { return m_parent->m_octomap.getProbMissLog(); }
124 
125  /// @return minimum threshold for occupancy clamping in the sensor model (probability)
126  double getClampingThresMin() const { if(m_parent.get()) return m_parent->m_octomap.getClampingThresMin(); else return this->clampingThresMin; }
127  /// @return minimum threshold for occupancy clamping in the sensor model (logodds)
128  float getClampingThresMinLog() const { return m_parent->m_octomap.getClampingThresMinLog(); }
129  /// @return maximum threshold for occupancy clamping in the sensor model (probability)
130  double getClampingThresMax() const { if(m_parent.get()) return m_parent->m_octomap.getClampingThresMax(); else return this->clampingThresMax; }
131  /// @return maximum threshold for occupancy clamping in the sensor model (logodds)
132  float getClampingThresMaxLog() const { return m_parent->m_octomap.getClampingThresMaxLog(); }
133 
134  private:
136 
137  double occupancyThres; // sets the threshold for occupancy (sensor model) (Default=0.5)
138  double probHit; // sets the probablility for a "hit" (will be converted to logodds) - sensor model (Default=0.7)
139  double probMiss; // sets the probablility for a "miss" (will be converted to logodds) - sensor model (Default=0.4)
140  double clampingThresMin; // sets the minimum threshold for occupancy clamping (sensor model) (Default=0.1192, -2 in log odds)
141  double clampingThresMax; // sets the maximum threshold for occupancy clamping (sensor model) (Default=0.971, 3.5 in log odds)
142  };
143 
144  TInsertionOptions insertionOptions; //!< The options used when inserting observations in the map
145 
146  /** Options used when evaluating "computeObservationLikelihood"
147  * \sa CObservation::computeObservationLikelihood
148  */
150  {
151  /** Initilization of default parameters
152  */
154  virtual ~TLikelihoodOptions() {}
155 
156  /** See utils::CLoadableOptions */
157  void loadFromConfigFile(
158  const mrpt::utils::CConfigFileBase &source,
159  const std::string &section);
160 
161  /** See utils::CLoadableOptions */
162  void dumpToTextStream(CStream &out) const;
163 
164  void writeToStream(CStream &out) const; //!< Binary dump to stream
165  void readFromStream(CStream &in); //!< Binary dump to stream
166 
167  uint32_t decimation; //!< Speed up the likelihood computation by considering only one out of N rays (default=1)
168  };
169 
170  TLikelihoodOptions likelihoodOptions;
171 
172  /** Returns true if the map is empty/no observation has been inserted.
173  */
174  virtual bool isEmpty() const;
175 
176 
177  // See docs in base class
178  virtual double computeObservationLikelihood( const CObservation *obs, const CPose3D &takenFrom );
179 
180  virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const;
181 
182  /** Options for the conversion of a mrpt::slam::COctoMap into a mrpt::opengl::COctoMapVoxels */
184  {
185  bool generateGridLines; //!< Generate grid lines for all octree nodes, useful to draw the "structure" of the octree, but computationally costly (Default: false)
186 
187  bool generateOccupiedVoxels; //!< Generate voxels for the occupied volumes (Default=true)
188  bool visibleOccupiedVoxels; //!< Set occupied voxels visible (requires generateOccupiedVoxels=true) (Default=true)
189 
190  bool generateFreeVoxels; //!< Generate voxels for the freespace (Default=true)
191  bool visibleFreeVoxels; //!< Set free voxels visible (requires generateFreeVoxels=true) (Default=true)
192 
194  generateGridLines (false),
195  generateOccupiedVoxels (true),
196  visibleOccupiedVoxels (true),
197  generateFreeVoxels (true),
198  visibleFreeVoxels (true)
199  { }
200 
201  void writeToStream(CStream &out) const; //!< Binary dump to stream
202  void readFromStream(CStream &in); //!< Binary dump to stream
203  };
204 
205  TRenderingOptions renderingOptions;
206 
207  /** Returns a 3D object representing the map.
208  * \sa renderingOptions
209  */
210  virtual void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj ) const
211  {
212  mrpt::opengl::COctoMapVoxelsPtr gl_obj = mrpt::opengl::COctoMapVoxels::Create();
213  this->getAsOctoMapVoxels(*gl_obj);
214  outObj->insert(gl_obj);
215  }
216 
217  /** Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.
218  * \sa renderingOptions
219  */
220  virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const = 0;
221 
222  /** Check whether the given point lies within the volume covered by the octomap (that is, whether it is "mapped") */
223  bool isPointWithinOctoMap(const float x,const float y,const float z) const
224  {
225  octomap::OcTreeKey key;
226  return m_octomap.coordToKeyChecked(octomap::point3d(x,y,z), key);
227  }
228 
229  /** Get the occupancy probability [0,1] of a point
230  * \return false if the point is not mapped, in which case the returned "prob" is undefined. */
231  bool getPointOccupancy(const float x,const float y,const float z, double &prob_occupancy) const;
232 
233  /** Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false), using the log-odds parameters in \a insertionOptions */
234  void updateVoxel(const double x, const double y, const double z, bool occupied)
235  {
236  m_octomap.updateNode(x,y,z, occupied);
237  }
238 
239  /** Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the sensor (the origin of the rays) in this map's frame of reference.
240  * Insertion parameters can be found in \a insertionOptions.
241  * \sa The generic observation insertion method CMetricMap::insertObservation()
242  */
243  void insertPointCloud(const CPointsMap &ptMap, const float sensor_x,const float sensor_y,const float sensor_z);
244 
245  /** Just like insertPointCloud but with a single ray. */
246  void insertRay(const float end_x,const float end_y,const float end_z,const float sensor_x,const float sensor_y,const float sensor_z)
247  {
248  m_octomap.insertRay( octomap::point3d(sensor_x,sensor_y,sensor_z), octomap::point3d(end_x,end_y,end_z), insertionOptions.maxrange,insertionOptions.pruning);
249  }
250 
251  /** Performs raycasting in 3d, similar to computeRay().
252  *
253  * A ray is cast from origin with a given direction, the first occupied
254  * cell is returned (as center coordinate). If the starting coordinate is already
255  * occupied in the tree, this coordinate will be returned as a hit.
256  *
257  * @param origin starting coordinate of ray
258  * @param direction A vector pointing in the direction of the raycast. Does not need to be normalized.
259  * @param end returns the center of the cell that was hit by the ray, if successful
260  * @param ignoreUnknownCells whether unknown cells are ignored. If false (default), the raycast aborts when an unkown cell is hit.
261  * @param maxRange Maximum range after which the raycast is aborted (<= 0: no limit, default)
262  * @return whether or not an occupied cell was hit
263  */
264  bool castRay(
265  const mrpt::math::TPoint3D & origin,
266  const mrpt::math::TPoint3D & direction,
268  bool ignoreUnknownCells=false,
269  double maxRange=-1.0) const;
270 
271  /** @name Direct access to octomap library methods
272  @{ */
273 
274  double getResolution() const { return m_octomap.getResolution(); }
275  unsigned int getTreeDepth () const { return m_octomap.getTreeDepth(); }
276  /// \return The number of nodes in the tree
277  size_t size() const { return m_octomap.size(); }
278  /// \return Memory usage of the complete octree in bytes (may vary between architectures)
279  size_t memoryUsage() const { return m_octomap.memoryUsage(); }
280  /// \return Memory usage of the a single octree node
281  size_t memoryUsageNode() const { return m_octomap.memoryUsageNode(); }
282  /// \return Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)
283  size_t memoryFullGrid() const { return m_octomap.memoryFullGrid(); }
284  double volume() const { return m_octomap.volume(); }
285  /// Size of OcTree (all known space) in meters for x, y and z dimension
286  void getMetricSize(double& x, double& y, double& z) { return m_octomap.getMetricSize(x,y,z); }
287  /// Size of OcTree (all known space) in meters for x, y and z dimension
288  void getMetricSize(double& x, double& y, double& z) const { return m_octomap.getMetricSize(x,y,z); }
289  /// minimum value of the bounding box of all known space in x, y, z
290  void getMetricMin(double& x, double& y, double& z) { return m_octomap.getMetricMin(x,y,z); }
291  /// minimum value of the bounding box of all known space in x, y, z
292  void getMetricMin(double& x, double& y, double& z) const { return m_octomap.getMetricMin(x,y,z); }
293  /// maximum value of the bounding box of all known space in x, y, z
294  void getMetricMax(double& x, double& y, double& z) { return m_octomap.getMetricMax(x,y,z); }
295  /// maximum value of the bounding box of all known space in x, y, z
296  void getMetricMax(double& x, double& y, double& z) const { return m_octomap.getMetricMax(x,y,z); }
297 
298  /// Traverses the tree to calculate the total number of nodes
299  size_t calcNumNodes() const { return m_octomap.calcNumNodes(); }
300 
301  /// Traverses the tree to calculate the total number of leaf nodes
302  size_t getNumLeafNodes() const { return m_octomap.getNumLeafNodes(); }
303 
304  /** @} */
305 
306 
307  protected:
308  virtual void internal_clear() { m_octomap.clear(); }
309 
310  /** Builds the list of 3D points in global coordinates for a generic observation. Used for both, insertObservation() and computeLikelihood().
311  * \param[out] point3d_sensorPt Is a pointer to a "point3D".
312  * \param[out] ptr_scan Is in fact a pointer to "octomap::Pointcloud". Not declared as such to avoid headers dependencies in user code.
313  * \return false if the observation kind is not applicable.
314  */
315  bool internal_build_PointCloud_for_observation(const CObservation *obs,const CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const;
316 
317  OCTREE m_octomap; //!< The actual octo-map object.
318 
319  }; // End of class def.
320  } // End of namespace
321 } // End of namespace
322 
323 #include "COctoMapBase_impl.h"
324 
325 #endif
void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
Definition: COctoMapBase.h:294
void readFromStream(CStream &in)
Binary dump to stream.
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section)
See utils::CLoadableOptions.
size_t memoryUsageNode() const
Definition: COctoMapBase.h:281
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section)
See utils::CLoadableOptions.
Options used when evaluating "computeObservationLikelihood".
Definition: COctoMapBase.h:149
EIGEN_STRONG_INLINE iterator end()
Definition: eigen_plugins.h:27
void dumpToTextStream(CStream &out) const
See utils::CLoadableOptions.
TInsertionOptions & operator=(const TInsertionOptions &o)
Definition: COctoMapBase.h:78
mrpt::utils::ignored_copy_ptr< myself_t > m_parent
Definition: COctoMapBase.h:135
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...
virtual void internal_clear()
Internal method called by clear()
Definition: COctoMapBase.h:308
double maxrange
maximum range for how long individual beams are inserted (default -1: complete beam) ...
Definition: COctoMapBase.h:97
void setClampingThresMin(double thresProb)
(key name in .ini files: "clampingThresMin")sets the minimum threshold for occupancy clamping (sensor...
Definition: COctoMapBase.h:107
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
void setOccupancyThres(double prob)
(key name in .ini files: "occupancyThres") sets the threshold for occupancy (sensor model) (Default=0...
Definition: COctoMapBase.h:101
double getResolution() const
Definition: COctoMapBase.h:274
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
Definition: COctoMapBase.h:302
OCTREE & getOctomap()
Get a reference to the internal octomap object.
Definition: COctoMapBase.h:67
void readFromStream(CStream &in)
Binary dump to stream.
TInsertionOptions()
Especial constructor, not attached to a real COctoMap object: used only in limited situations...
COctoMapBase< OCTREE, OCTREE_NODE > myself_t
The type of this MRPT class.
Definition: COctoMapBase.h:49
bool isPointWithinOctoMap(const float x, const float y, const float z) const
Check whether the given point lies within the volume covered by the octomap (that is...
Definition: COctoMapBase.h:223
OCTREE octree_t
The type of the octree class in the "octomap" library.
Definition: COctoMapBase.h:50
void dumpToTextStream(CStream &out) const
See utils::CLoadableOptions.
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const =0
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...
virtual double computeObservationLikelihood(const CObservation *obs, const CPose3D &takenFrom)
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
This class allows loading and storing values and vectors of different types from a configuration text...
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:83
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::slam::COctoMap).
virtual bool isEmpty() const
Returns true if the map is empty/no observation has been inserted.
void getMetricMax(double &x, double &y, double &z) const
maximum value of the bounding box of all known space in x, y, z
Definition: COctoMapBase.h:296
unsigned int getTreeDepth() const
Definition: COctoMapBase.h:275
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
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().
With this struct options are provided to the observation insertion process.
Definition: COctoMapBase.h:72
void writeToStream(CStream &out) const
Binary dump to stream.
void getMetricMin(double &x, double &y, double &z)
minimum value of the bounding box of all known space in x, y, z
Definition: COctoMapBase.h:290
Declares a class that represents any robot's observation.
Definition: CObservation.h:52
void setProbMiss(double prob)
(key name in .ini files: "probMiss")sets the probablility for a "miss" (will be converted to logodds)...
Definition: COctoMapBase.h:105
bool generateOccupiedVoxels
Generate voxels for the occupied volumes (Default=true)
Definition: COctoMapBase.h:187
void updateVoxel(const double x, const double y, const double z, bool occupied)
Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false)...
Definition: COctoMapBase.h:234
void getMetricMin(double &x, double &y, double &z) const
minimum value of the bounding box of all known space in x, y, z
Definition: COctoMapBase.h:292
void setClampingThresMax(double thresProb)
(key name in .ini files: "clampingThresMax")sets the maximum threshold for occupancy clamping (sensor...
Definition: COctoMapBase.h:109
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan...
Definition: Pointcloud.h:63
TLikelihoodOptions likelihoodOptions
Definition: COctoMapBase.h:170
bool pruning
whether the tree is (losslessly) pruned after insertion (default: true)
Definition: COctoMapBase.h:98
size_t memoryUsage() const
Definition: COctoMapBase.h:279
void insertRay(const float end_x, const float end_y, const float end_z, const float sensor_x, const float sensor_y, const float sensor_z)
Just like insertPointCloud but with a single ray.
Definition: COctoMapBase.h:246
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
Definition: COctoMapBase.h:299
double volume() const
Definition: COctoMapBase.h:284
virtual void getAs3DObject(mrpt::opengl::CSetOfObjectsPtr &outObj) const
Returns a 3D object representing the map.
Definition: COctoMapBase.h:210
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=1) ...
Definition: COctoMapBase.h:167
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
Definition: COctoMapBase.h:144
OCTREE_NODE octree_node_t
The type of nodes in the octree, in the "octomap" library.
Definition: COctoMapBase.h:51
TRenderingOptions renderingOptions
Definition: COctoMapBase.h:205
OcTreeKey is a container class for internal key addressing.
Definition: OcTreeKey.h:68
TLikelihoodOptions()
Initilization of default parameters.
bool visibleOccupiedVoxels
Set occupied voxels visible (requires generateOccupiedVoxels=true) (Default=true) ...
Definition: COctoMapBase.h:188
OCTREE m_octomap
The actual octo-map object.
Definition: COctoMapBase.h:317
size_t size() const
Definition: COctoMapBase.h:277
void getMetricSize(double &x, double &y, double &z) const
Size of OcTree (all known space) in meters for x, y and z dimension.
Definition: COctoMapBase.h:288
Options for the conversion of a mrpt::slam::COctoMap into a mrpt::opengl::COctoMapVoxels.
Definition: COctoMapBase.h:183
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:59
COctoMapBase(const double resolution=0.10)
Constructor, defines the resolution of the octomap (length of each voxel side)
Definition: COctoMapBase.h:55
bool generateFreeVoxels
Generate voxels for the freespace (Default=true)
Definition: COctoMapBase.h:190
bool visibleFreeVoxels
Set free voxels visible (requires generateFreeVoxels=true) (Default=true)
Definition: COctoMapBase.h:191
static COctoMapVoxelsPtr Create()
Lightweight 3D point.
void writeToStream(CStream &out) const
Binary dump to stream.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:46
A wrapper class for pointers whose copy operations from other objects of the same type are ignored...
size_t memoryFullGrid() const
Definition: COctoMapBase.h:283
void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
Definition: COctoMapBase.h:286
void setProbHit(double prob)
(key name in .ini files: "probHit")sets the probablility for a "hit" (will be converted to logodds) -...
Definition: COctoMapBase.h:103
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
bool generateGridLines
Generate grid lines for all octree nodes, useful to draw the "structure" of the octree, but computationally costly (Default: false)
Definition: COctoMapBase.h:185
bool internal_build_PointCloud_for_observation(const CObservation *obs, const CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const
Builds the list of 3D points in global coordinates for a generic observation.
This class represents a three-dimensional vector.
Definition: Vector3.h:65



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014