10 #ifndef MRPT_CColouredOctoMap_H 11 #define MRPT_CColouredOctoMap_H 14 #include <octomap/octomap.h> 15 #include <octomap/ColorOcTree.h> 56 bool getPointColour(
const float x,
const float y,
const float z, uint8_t& r, uint8_t& g, uint8_t& b)
const;
59 void updateVoxelColour(
const double x,
const double y,
const double z,
const uint8_t r,
const uint8_t g,
const uint8_t b);
76 bool internal_insertObservation(const
mrpt::obs::CObservation *obs,const
mrpt::poses::CPose3D *robotPose) MRPT_OVERRIDE;
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
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).
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
void setVoxelColourMethod(TColourUpdate new_method)
Set the method used to update voxels colour.
TColourUpdate
This allows the user to select the desired method to update voxels colour.
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...
TColourUpdate getVoxelColourMethod()
Get the method used to update voxels colour.
Declares a virtual base class for all metric maps storage classes.
x y t t *t x y t t t x y t t t x *y t *t t x *y t *t t x y t t t x y t t t x(y+z)
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define MAP_DEFINITION_START(_CLASS_NAME_, _LINKAGE_)
Add a MAP_DEFINITION_START() ...