9 #ifndef OCTOMAP_OCTREE_STAMPED_H
10 #define OCTOMAP_OCTREE_STAMPED_H
double resolution
in meters
Base implementation for Occupancy Octrees (e.g.
Static member object which ensures that this OcTree's prototype ends up in the classIDMapping only on...
OctoMap: A probabilistic, flexible, and compact 3D mapping library for robotic systems.
std::string getTreeType() const
returns actual class name as string for identification
OcTreeNodeStamped(const OcTreeNodeStamped &rhs)
void degradeOutdatedNodes(unsigned int time_thres)
OcTreeDataNode< float > ** children
pointer to array of children, may be NULL
void updateOccupancyChildren()
void integrateMissNoTime(OcTreeNodeStamped *node) const
bool operator==(const OcTreeNodeStamped &rhs) const
float getMaxChildLogOdds() const
StaticMemberInitializer()
void setTimestamp(unsigned int timestamp)
OcTreeNodeStamped * getChild(unsigned int i)
OcTreeNode * getChild(unsigned int i)
T value
stored data (payload)
unsigned int getLastUpdateTime()
static void registerTreeType(AbstractOcTree *tree)
bool createChild(unsigned int i)
unsigned int getTimestamp() const
OcTreeStamped * create() const
virtual constructor: creates a new object of same type (Covariant return type requires an up-to-date ...
Nodes to be used in OcTree.
const OcTreeNodeStamped * getChild(unsigned int i) const
OcTreeStamped(double resolution)
Default constructor, sets resolution of leafs.
virtual void updateNodeLogOdds(OcTreeNodeStamped *node, const float &update) const
static StaticMemberInitializer ocTreeStampedMemberInit
to ensure static initialization (only once)
void setLogOdds(float l)
sets log odds occupancy of node