class mrpt::maps::COctoMap
Overview
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the “octomap” C++ library.
This version only stores occupancy information at each octree node. See the base class mrpt::maps::COctoMapBase.
The octomap library was presented in [8]
See also:
CMetricMap, the example in “MRPT/mrpt_examples_cpp/octomap_simple”
#include <mrpt/maps/COctoMap.h> class COctoMap: public mrpt::maps::COctoMapBase { public: // typedefs typedef std::shared_ptr<mrpt::maps ::COctoMap> Ptr; typedef std::shared_ptr<const mrpt::maps ::COctoMap> ConstPtr; typedef std::unique_ptr<mrpt::maps ::COctoMap> UniquePtr; typedef std::unique_ptr<const mrpt::maps ::COctoMap> ConstUniquePtr; // structs struct TMapDefinition; struct TMapDefinitionBase; // fields static constexpr const char* className = "mrpt::maps" "::" "COctoMap"; static const size_t m_private_map_register_id = mrpt::maps::internal::TMetricMapTypesRegistry::Instance().doRegister("mrpt::maps::COctoMap,octoMap" ,& mrpt::maps::COctoMap ::MapDefinition,& mrpt::maps::COctoMap ::internal_CreateFromMapDefinition); // construction COctoMap(const double resolution = 0.10); // methods static constexpr auto getClassName(); static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); static std::shared_ptr<CObject> CreateObject(); template <typename... Args> static Ptr Create(Args&&... args); template <typename Alloc, typename... Args> static Ptr CreateAlloc( const Alloc& alloc, Args&&... args ); template <typename... Args> static UniquePtr CreateUnique(Args&&... args); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual mrpt::rtti::CObject* clone() const; static std::shared_ptr<mrpt::maps::TMetricMapInitializer> MapDefinition(); static std::shared_ptr<COctoMap> CreateFromMapDefinition(const mrpt::maps::TMetricMapInitializer& def); static std::shared_ptr<mrpt::maps::CMetricMap> internal_CreateFromMapDefinition(const mrpt::maps::TMetricMapInitializer& def); 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 ); void updateVoxel(const double x, const double y, const double z, bool occupied); bool isPointWithinOctoMap(const float x, const float y, const float z) const; double getResolution() const; unsigned int getTreeDepth() const; size_t size() const; size_t memoryUsage() const; size_t memoryUsageNode() const; size_t memoryFullGrid() const; double volume(); void getMetricSize(double& x, double& y, double& z); void getMetricSize(double& x, double& y, double& z) const; void getMetricMin(double& x, double& y, double& z); void getMetricMin(double& x, double& y, double& z) const; void getMetricMax(double& x, double& y, double& z); void getMetricMax(double& x, double& y, double& z) const; size_t calcNumNodes() const; size_t getNumLeafNodes() const; virtual void setOccupancyThres(double prob); virtual void setProbHit(double prob); virtual void setProbMiss(double prob); virtual void setClampingThresMin(double thresProb); virtual void setClampingThresMax(double thresProb); virtual double getOccupancyThres() const; virtual float getOccupancyThresLog() const; virtual double getProbHit() const; virtual float getProbHitLog() const; virtual double getProbMiss() const; virtual float getProbMissLog() const; virtual double getClampingThresMin() const; virtual float getClampingThresMinLog() const; virtual double getClampingThresMax() const; virtual float getClampingThresMaxLog() const; virtual void getAsOctoMapVoxels(mrpt::viz::COctoMapVoxels& gl_obj) const; virtual bool isEmpty() const; };
Inherited Members
public: // typedefs typedef std::shared_ptr<CObject> Ptr; typedef std::shared_ptr<const CObject> ConstPtr; typedef std::shared_ptr<CSerializable> Ptr; typedef std::shared_ptr<const CSerializable> ConstPtr; typedef COctoMapBase<octree_t, octree_node_t> myself_t; // structs struct TInsertionOptions; struct TLikelihoodOptions; struct TRenderingOptions; // fields TLikelihoodOptions likelihoodOptions; TRenderingOptions renderingOptions; // methods static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); Visualizable& operator = (const Visualizable&); Visualizable& operator = (Visualizable&&); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual bool isEmpty() const = 0; virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0; virtual std::string asString() const = 0; virtual void getVisualizationInto(mrpt::viz::CSetOfObjects& o) const = 0; virtual void getAsOctoMapVoxels(mrpt::viz::COctoMapVoxels& gl_obj) const = 0; virtual void setOccupancyThres(double prob) = 0; virtual void setProbHit(double prob) = 0; virtual void setProbMiss(double prob) = 0; virtual void setClampingThresMin(double thresProb) = 0; virtual void setClampingThresMax(double thresProb) = 0; virtual double getOccupancyThres() const = 0; virtual float getOccupancyThresLog() const = 0; virtual double getProbHit() const = 0; virtual float getProbHitLog() const = 0; virtual double getProbMiss() const = 0; virtual float getProbMissLog() const = 0; virtual double getClampingThresMin() const = 0; virtual float getClampingThresMinLog() const = 0; virtual double getClampingThresMax() const = 0; virtual float getClampingThresMaxLog() const = 0;
Typedefs
typedef std::shared_ptr<mrpt::maps ::COctoMap> Ptr
A type for the associated smart pointer.
Fields
static const size_t m_private_map_register_id = mrpt::maps::internal::TMetricMapTypesRegistry::Instance().doRegister("mrpt::maps::COctoMap,octoMap" ,& mrpt::maps::COctoMap ::MapDefinition,& mrpt::maps::COctoMap ::internal_CreateFromMapDefinition)
ID used to initialize class registration (just ignore it)
Construction
COctoMap(const double resolution = 0.10)
Default constructor.
Methods
virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const
Returns information about the class of an object in runtime.
virtual mrpt::rtti::CObject* clone() const
Returns a deep copy (clone) of the object, indepently of its class.
static std::shared_ptr<mrpt::maps::TMetricMapInitializer> MapDefinition()
Returns default map definition initializer.
See * mrpt::maps::TMetricMapInitializer
static std::shared_ptr<COctoMap> CreateFromMapDefinition(const mrpt::maps::TMetricMapInitializer& def)
Constructor from a map definition structure: initializes the map and * its parameters accordingly.
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.
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), using the log-odds parameters in insertionOptions.
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, whether it is “mapped”)
size_t size() const
Returns:
The number of nodes in the tree
size_t memoryUsage() const
Returns:
Memory usage of the complete octree in bytes (may vary between architectures)
size_t memoryUsageNode() const
Returns:
Memory usage of the a single octree node
size_t memoryFullGrid() const
Returns:
Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)
void getMetricSize(double& x, double& y, double& z)
Size of OcTree (all known space) in meters for x, y and z dimension.
void getMetricSize(double& x, double& y, double& z) const
Size of OcTree (all known space) in meters for x, y and z dimension.
void getMetricMin(double& x, double& y, double& z)
minimum value of the bounding box of all known space in x, y, z
void getMetricMin(double& x, double& y, double& z) const
minimum value of the bounding box of all known space in x, y, z
void getMetricMax(double& x, double& y, double& z)
maximum value of the bounding box of all known space in x, y, z
void getMetricMax(double& x, double& y, double& z) const
maximum value of the bounding box of all known space in x, y, z
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
virtual void getAsOctoMapVoxels(mrpt::viz::COctoMapVoxels& gl_obj) const
Builds a renderizable representation of the octomap as a mrpt::viz::COctoMapVoxels object.
virtual bool isEmpty() const
Returns true if the map is empty/no observation has been inserted.