21 class ColorOcTreeNode;
37 :
public COctoMapBase<octomap::ColorOcTree, octomap::ColorOcTreeNode>
67 const float x,
const float y,
const float z, uint8_t& r, uint8_t& g,
72 const double x,
const double y,
const double z,
const uint8_t r,
73 const uint8_t g,
const uint8_t b);
90 mrpt::maps::CColouredOctoMap::TInsertionOptions
92 mrpt::maps::CColouredOctoMap::TLikelihoodOptions
103 const float end_x,
const float end_y,
const float end_z,
104 const float sensor_x,
const float sensor_y,
const float sensor_z);
109 const double x,
const double y,
const double z,
bool occupied);
113 const float x,
const float y,
const float z)
const;
134 void getMetricMin(
double& x,
double& y,
double& z)
const;
138 void getMetricMax(
double& x,
double& y,
double& z)
const;
double getResolution() const
unsigned int getTreeDepth() const
void setClampingThresMax(double thresProb) override
double getProbMiss() const override
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
float getClampingThresMinLog() const override
double getProbHit() const override
mrpt::maps::CColouredOctoMap::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
size_t memoryFullGrid() const
double getClampingThresMin() 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 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 internal_clear() override
Internal method called by clear()
void setClampingThresMin(double thresProb) override
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).
void setVoxelColourMethod(TColourUpdate new_method)
Set the method used to update voxels colour.
mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts
meters)
void updateVoxelColour(const double x, const double y, const double z, const uint8_t r, const uint8_t g, const uint8_t b)
Manually update the colour of the voxel at (x,y,z)
double getOccupancyThres() const override
bool getPointColour(const float x, const float y, const float z, uint8_t &r, uint8_t &g, uint8_t &b) const
Get the RGB colour of a point.
bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
TColourUpdate
This allows the user to select the desired method to update voxels colour.
void setProbMiss(double prob) override
void setProbHit(double prob) override
TColourUpdate m_colour_method
float getClampingThresMaxLog() const override
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
TColourUpdate getVoxelColourMethod()
Get the method used to update voxels colour.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
float getProbMissLog() const override
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose) override
Internal method called by insertObservation()
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
float getOccupancyThresLog() const override
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
void setOccupancyThres(double prob) override
size_t memoryUsageNode() const
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const override
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
#define MAP_DEFINITION_END(_CLASS_NAME_)
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.
size_t memoryUsage() const
float getProbHitLog() const override
double getClampingThresMax() const override
~CColouredOctoMap() override
Destructor.
CColouredOctoMap(const double resolution=0.10)
Default constructor.