46 COctoMap(
const double resolution = 0.10);
56 mrpt::maps::COctoMap::TInsertionOptions
58 mrpt::maps::COctoMap::TLikelihoodOptions
69 const float end_x,
const float end_y,
const float end_z,
70 const float sensor_x,
const float sensor_y,
const float sensor_z);
75 const double x,
const double y,
const double z,
bool occupied);
79 const float x,
const float y,
const float z)
const;
100 void getMetricMin(
double& x,
double& y,
double& z)
const;
104 void getMetricMax(
double& x,
double& y,
double& z)
const;
void setClampingThresMax(double thresProb) override
double getOccupancyThres() const override
void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
float getClampingThresMaxLog() const override
size_t memoryUsageNode() const
double getClampingThresMin() const override
double getProbHit() const override
void setProbHit(double prob) override
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
size_t memoryFullGrid() const
float getClampingThresMinLog() const override
float getOccupancyThresLog() const override
void setClampingThresMin(double thresProb) override
void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose) override
Internal method called by insertObservation()
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
double getClampingThresMax() const override
float getProbMissLog() const override
void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const override
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...
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)...
void getMetricMin(double &x, double &y, double &z)
minimum value of the bounding box of all known space in x, y, z
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 internal_clear() override
Internal method called by clear()
void setOccupancyThres(double prob) override
mrpt::maps::COctoMap::TInsertionOptions insertionOpts
meters)
mrpt::maps::COctoMap::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
double getResolution() const
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
double getProbMiss() const override
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...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
void setProbMiss(double prob) override
size_t memoryUsage() const
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
unsigned int getTreeDepth() const
~COctoMap() override
Destructor.
#define MAP_DEFINITION_END(_CLASS_NAME_)
float getProbHitLog() const override
COctoMap(const double resolution=0.10)
Default constructor.