Main MRPT website > C++ reference for MRPT 1.9.9
COctoMap.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 #ifndef MRPT_COctoMap_H
11 #define MRPT_COctoMap_H
12 
13 #include <mrpt/maps/COctoMapBase.h>
14 
15 #include <mrpt/maps/CMetricMap.h>
18 #include <octomap/octomap.h>
19 #include <mrpt/obs/obs_frwds.h>
20 
21 namespace mrpt
22 {
23 namespace maps
24 {
25 /** A three-dimensional probabilistic occupancy grid, implemented as an
26  * octo-tree with the "octomap" C++ library.
27  * This version only stores occupancy information at each octree node. See the
28  * base class mrpt::maps::COctoMapBase.
29  *
30  * \sa CMetricMap, the example in "MRPT/samples/octomap_simple"
31  * \ingroup mrpt_maps_grp
32  */
33 class COctoMap : public COctoMapBase<octomap::OcTree, octomap::OcTreeNode>
34 {
36 
37  public:
38  /** Default constructor */
39  COctoMap(const double resolution = 0.10);
40  /** Destructor */
41  virtual ~COctoMap();
42 
43  virtual void getAsOctoMapVoxels(
44  mrpt::opengl::COctoMapVoxels& gl_obj) const override;
45 
47  /** The finest resolution of the octomap (default: 0.10 meters) */
48  double resolution;
49  /** Observations insertion options */
50  mrpt::maps::COctoMap::TInsertionOptions insertionOpts;
51  /** Probabilistic observation likelihood options */
52  mrpt::maps::COctoMap::TLikelihoodOptions likelihoodOpts;
54 
55  protected:
57  const mrpt::obs::CObservation* obs,
58  const mrpt::poses::CPose3D* robotPose) override;
59 }; // End of class def.
60 } // End of namespace
61 
62 } // End of namespace
63 
64 #endif
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose) override
Internal method called by insertObservation()
Definition: COctoMap.cpp:145
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMapBase.h:48
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const override
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...
Definition: COctoMap.cpp:161
virtual ~COctoMap()
Destructor.
Definition: COctoMap.cpp:82
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMap.h:33
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
COctoMap(const double resolution=0.10)
Default constructor.
Definition: COctoMap.cpp:74



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