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