9 #ifndef OCTOMAP_COUNTING_OCTREE_HH 10 #define OCTOMAP_COUNTING_OCTREE_HH 110 void getCentersMinHits(
point3d_list& node_centers,
unsigned int min_hits)
const;
114 void getCentersMinHitsRecurs(
point3d_list& node_centers,
115 unsigned int& min_hits,
116 unsigned int max_depth,
void setCount(unsigned c)
OctoMap: A probabilistic, flexible, and compact 3D mapping library for robotic systems.
CountingOcTree(double resolution)
Default constructor, sets resolution of leafs.
An Octree-node which stores an internal counter per node / volume.
An AbstractOcTree which stores an internal counter per node / volume.
CountingOcTreeNode * getChild(unsigned int i)
StaticMemberInitializer()
unsigned int getValue() const
unsigned int getCount() const
void setValue(unsigned intv)
sets value to be stored in the node
std::list< octomath::Vector3 > point3d_list
unsigned int value
stored data (payload)
static void registerTreeType(AbstractOcTree *tree)
static StaticMemberInitializer countingOcTreeMemberInit
static member to ensure static initialization (only once)
OcTreeKey is a container class for internal key addressing.
Static member object which ensures that this OcTree's prototype ends up in the classIDMapping only on...
bool createChild(unsigned int i)
Basic node in the OcTree that can hold arbitrary data of type T in value.
const CountingOcTreeNode * getChild(unsigned int i) const
OcTreeDataNode< T > * getChild(unsigned int i)
This class represents a three-dimensional vector.