45 template <
class NODE,
class I>
56 template <
class NODE,
class I>
67 template <
class NODE,
class I>
73 template <
class NODE,
class I>
75 root(NULL), tree_depth(rhs.tree_depth), tree_max_val(rhs.tree_max_val),
76 resolution(rhs.resolution), tree_size(rhs.tree_size)
86 template <
class NODE,
class I>
90 for (
unsigned i = 0; i< 3; i++){
91 max_value[i] = -(std::numeric_limits<double>::max( ));
92 min_value[i] = std::numeric_limits<double>::max( );
102 if (omp_get_thread_num() == 0){
103 this->
keyrays.resize(omp_get_num_threads());
113 template <
class NODE,
class I>
115 NODE* this_root =
root;
117 other.
root = this_root;
124 template <
class NODE,
class I>
137 for (; it !=
end; ++it, ++other_it){
138 if (other_it == other_end)
143 || !(*it == *other_it))
149 if (other_it != other_end)
155 template <
class NODE,
class I>
172 template <
class NODE,
class I>
174 assert(childIdx < 8);
175 if (node->children == NULL) {
178 assert (node->children[childIdx] == NULL);
179 NODE* newNode =
new NODE();
188 template <
class NODE,
class I>
190 assert((childIdx < 8) && (node->children != NULL));
191 assert(node->children[childIdx] != NULL);
192 delete static_cast<NODE*
>(node->children[childIdx]);
193 node->children[childIdx] = NULL;
199 template <
class NODE,
class I>
201 assert((childIdx < 8) && (node->children != NULL));
202 assert(node->children[childIdx] != NULL);
203 return static_cast<NODE*
>(node->children[childIdx]);
206 template <
class NODE,
class I>
208 assert((childIdx < 8) && (node->children != NULL));
209 assert(node->children[childIdx] != NULL);
210 return static_cast<const NODE*
>(node->children[childIdx]);
213 template <
class NODE,
class I>
224 for (
unsigned int i = 1; i<8; i++) {
234 template <
class NODE,
class I>
236 assert(childIdx < 8);
237 if ((node->children != NULL) && (node->children[childIdx] != NULL))
243 template <
class NODE,
class I>
245 if (node->children == NULL)
248 for (
unsigned int i = 0; i<8; i++){
249 if (node->children[i] != NULL)
256 template <
class NODE,
class I>
260 for (
unsigned int k=0; k<8; k++) {
262 newNode->copyData(*node);
266 template <
class NODE,
class I>
276 for (
unsigned int i=0;i<8;i++) {
279 delete[] node->children;
280 node->children = NULL;
285 template <
class NODE,
class I>
289 for (
unsigned int i=0; i<8; i++) {
290 node->children[i] = NULL;
296 template <
class NODE,
class I>
305 return ((keyval >> diff) << diff) + (1 << (diff-1)) +
tree_max_val;
309 template <
class NODE,
class I>
316 if (( scaled_coord >= 0) && (((
unsigned int) scaled_coord) < (2*
tree_max_val))) {
317 keyval = scaled_coord;
324 template <
class NODE,
class I>
331 if (( scaled_coord >= 0) && (((
unsigned int) scaled_coord) < (2*
tree_max_val))) {
332 keyval = scaled_coord;
339 template <
class NODE,
class I>
342 for (
unsigned int i=0;i<3;i++) {
348 template <
class NODE,
class I>
351 for (
unsigned int i=0;i<3;i++) {
357 template <
class NODE,
class I>
370 template <
class NODE,
class I>
383 template <
class NODE,
class I>
393 template <
class NODE,
class I>
403 return (floor( (
double(key)-
double(this->tree_max_val)) /
double(1 << (
tree_depth - depth)) ) + 0.5 ) * this->
getNodeSize(depth);
407 template <
class NODE,
class I>
415 return this->
search(key, depth);
420 template <
class NODE,
class I>
424 OCTOMAP_ERROR_STR(
"Error in search: ["<< x <<
" "<< y <<
" " << z <<
"] is out of OcTree bounds!");
428 return this->search(key, depth);
433 template <
class NODE,
class I>
449 NODE* curNode (
root);
474 template <
class NODE,
class I>
478 OCTOMAP_ERROR_STR(
"Error in deleteNode: ["<< value <<
"] is out of OcTree bounds!");
482 return this->deleteNode(key, depth);
487 template <
class NODE,
class I>
491 OCTOMAP_ERROR_STR(
"Error in deleteNode: ["<< x <<
" "<< y <<
" " << z <<
"] is out of OcTree bounds!");
500 template <
class NODE,
class I>
511 template <
class NODE,
class I>
522 template <
class NODE,
class I>
528 unsigned int num_pruned = 0;
535 template <
class NODE,
class I>
541 template <
class NODE,
class I>
555 << origin <<
" -> " <<
end <<
") out of bounds in computeRayKeys");
560 if (key_origin == key_end)
568 float length = (float) direction.
norm();
577 for(
unsigned int i=0; i < 3; ++i) {
579 if (direction(i) > 0.0) step[i] = 1;
580 else if (direction(i) < 0.0) step[i] = -1;
586 double voxelBorder = this->
keyToCoord(current_key[i]);
587 voxelBorder += (float) (step[i] * this->
resolution * 0.5);
589 tMax[i] = ( voxelBorder - origin(i) ) / direction(i);
590 tDelta[i] = this->resolution / fabs( direction(i) );
593 tMax[i] = std::numeric_limits<double>::max( );
594 tDelta[i] = std::numeric_limits<double>::max( );
606 if (tMax[0] < tMax[1]){
607 if (tMax[0] < tMax[2]) dim = 0;
611 if (tMax[1] < tMax[2]) dim = 1;
616 current_key[dim] += step[dim];
617 tMax[dim] += tDelta[dim];
619 assert (current_key[dim] < 2*this->tree_max_val);
622 if (current_key == key_end) {
630 double dist_from_origin = std::min(std::min(tMax[0], tMax[1]), tMax[2]);
633 if (dist_from_origin > length) {
650 template <
class NODE,
class I>
652 std::vector<point3d>& _ray) {
661 template <
class NODE,
class I>
666 if (node->children != NULL) {
667 for (
unsigned int i=0; i<8; i++) {
668 if (node->children[i] != NULL){
672 delete[] node->children;
673 node->children = NULL;
680 template <
class NODE,
class I>
682 if (depth >= max_depth)
711 node->updateOccupancyChildren();
718 template <
class NODE,
class I>
720 unsigned int max_depth,
unsigned int& num_pruned) {
724 if (depth < max_depth) {
725 for (
unsigned int i=0; i<8; i++) {
741 template <
class NODE,
class I>
743 unsigned int max_depth) {
744 if (depth >= max_depth)
754 for (
unsigned int i=0; i<8; i++) {
762 template <
class NODE,
class I>
770 template <
class NODE,
class I>
775 std::bitset<8> children;
776 for (
unsigned int i=0; i<8; i++) {
783 char children_char = (char) children.to_ulong();
784 s.write((
char*)&children_char,
sizeof(
char));
791 for (
unsigned int i=0; i<8; i++) {
792 if (children[i] == 1) {
800 template <
class NODE,
class I>
804 OCTOMAP_WARNING_STR(__FILE__ <<
":" << __LINE__ <<
"Warning: Input filestream not \"good\"");
823 template <
class NODE,
class I>
829 s.read((
char*)&children_char,
sizeof(
char));
830 std::bitset<8> children ((
unsigned long long) children_char);
836 for (
unsigned int i=0; i<8; i++) {
837 if (children[i] == 1){
849 template <
class NODE,
class I>
854 double size_x, size_y, size_z;
863 *
sizeof(
root->getValue()));
871 template <
class NODE,
class I>
874 double minX, minY, minZ;
875 double maxX, maxY, maxZ;
885 template <
class NODE,
class I>
888 double minX, minY, minZ;
889 double maxX, maxY, maxZ;
899 template <
class NODE,
class I>
912 for (
unsigned i = 0; i< 3; i++){
913 max_value[i] = -std::numeric_limits<double>::max();
914 min_value[i] = std::numeric_limits<double>::max();
918 end=this->end(); it!=
end; ++it)
921 double halfSize =
size/2.0;
922 double x = it.
getX() - halfSize;
923 double y = it.
getY() - halfSize;
924 double z = it.
getZ() - halfSize;
941 template <
class NODE,
class I>
949 template <
class NODE,
class I>
959 template <
class NODE,
class I>
961 mx = my = mz = std::numeric_limits<double>::max( );
970 end=this->end(); it!=
end; ++it) {
971 double halfSize = it.
getSize()/2.0;
972 double x = it.
getX() - halfSize;
973 double y = it.
getY() - halfSize;
974 double z = it.
getZ() - halfSize;
987 template <
class NODE,
class I>
989 mx = my = mz = -std::numeric_limits<double>::max( );
998 end=this->end(); it!=
end; ++it) {
999 double halfSize = it.
getSize()/2.0;
1000 double x = it.
getX() + halfSize;
1001 double y = it.
getY() + halfSize;
1002 double z = it.
getZ() + halfSize;
1015 template <
class NODE,
class I>
1025 template <
class NODE,
class I>
1029 for (
unsigned int i=0; i<8; ++i) {
1038 template <
class NODE,
class I>
1041 size_t num_inner_nodes =
tree_size - num_leaf_nodes;
1045 template <
class NODE,
class I>
1056 unsigned int steps[3];
1058 for (
int i=0;i<3;++i) {
1059 diff[i] = pmax_clamped(i) - pmin_clamped(i);
1060 steps[i] =
static_cast<unsigned int>(floor(diff[i] / step_size));
1066 for (
unsigned int x=0; x<steps[0]; ++x) {
1068 for (
unsigned int y=0; y<steps[1]; ++y) {
1070 for (
unsigned int z=0; z<steps[2]; ++z) {
1073 res = this->
search(p,depth);
1075 node_centers.push_back(p);
1078 p.
z() = pmin_clamped.
z();
1080 p.
y() = pmin_clamped.
y();
1085 template <
class NODE,
class I>
1094 template <
class NODE,
class I>
1101 size_t sum_leafs_children = 0;
1102 for (
unsigned int i=0; i<8; ++i) {
1107 return sum_leafs_children;
1111 template <
class NODE,
class I>
Definition OcTreeDataNode.h:43
Definition OcTreeKey.h:139
size_t sizeMax() const
Definition OcTreeKey.h:164
std::vector< OcTreeKey >::const_iterator const_iterator
Definition OcTreeKey.h:167
void addKey(const OcTreeKey &k)
Definition OcTreeKey.h:157
void reset()
Definition OcTreeKey.h:153
size_t size() const
Definition OcTreeKey.h:163
double getY() const
Definition OcTreeBaseImpl.h:127
unsigned getDepth() const
return depth of the current node
Definition OcTreeBaseImpl.h:139
const OcTreeKey & getKey() const
Definition OcTreeBaseImpl.h:142
double getZ() const
Definition OcTreeBaseImpl.h:131
double getX() const
Definition OcTreeBaseImpl.h:123
double getSize() const
Definition OcTreeBaseImpl.h:136
Iterator to iterate over all leafs of the tree.
Definition OcTreeBaseImpl.h:264
Iterator over the complete tree (inner nodes and leafs).
Definition OcTreeBaseImpl.h:208
OcTree base class, to be used with with any kind of OcTreeDataNode.
Definition OcTreeBaseImpl.h:75
size_t getNumLeafNodesRecurs(const NODE *parent) const
Definition OcTreeBaseImpl.hxx:1095
NODE * getNodeChild(NODE *node, unsigned int childIdx) const
Definition OcTreeBaseImpl.hxx:200
std::istream & readData(std::istream &s)
Read all nodes from the input stream (without file header), for this the tree needs to be already cre...
Definition OcTreeBaseImpl.hxx:801
const unsigned int tree_max_val
Definition OcTreeBaseImpl.h:546
double max_value[3]
max in x, y, z
Definition OcTreeBaseImpl.h:556
key_type coordToKey(double coordinate) const
Converts from a single coordinate into a discrete key.
Definition OcTreeBaseImpl.h:357
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
Definition OcTreeBaseImpl.hxx:340
virtual void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
Definition OcTreeBaseImpl.hxx:950
virtual void getMetricMin(double &x, double &y, double &z)
minimum value of the bounding box of all known space in x, y, z
Definition OcTreeBaseImpl.hxx:942
virtual size_t memoryUsage() const
Definition OcTreeBaseImpl.hxx:1039
void deleteNodeRecurs(ColorOcTreeNode *node)
Definition OcTreeBaseImpl.hxx:662
bool nodeChildExists(const NODE *node, unsigned int childIdx) const
Safe test if node has a child at index childIdx.
Definition OcTreeBaseImpl.hxx:235
virtual void prune()
Lossless compression of the octree: A node will replace all of its eight children if they have identi...
Definition OcTreeBaseImpl.hxx:523
bool deleteNode(double x, double y, double z, unsigned int depth=0)
Delete a node (if exists) given a 3d point.
Definition OcTreeBaseImpl.hxx:488
const iterator end() const
Definition OcTreeBaseImpl.h:329
double keyToCoord(key_type key, unsigned depth) const
converts from a discrete key at a given depth into a coordinate corresponding to the key's center
Definition OcTreeBaseImpl.hxx:394
virtual void expandNode(NODE *node)
Expands a node (reverse of pruning): All children are created and their occupancy probability is set ...
Definition OcTreeBaseImpl.hxx:257
void setResolution(double r)
Change the resolution of the octree, scaling all voxels. This will not preserve the (metric) scale!
Definition OcTreeBaseImpl.hxx:156
const tree_iterator end_tree() const
Definition OcTreeBaseImpl.h:350
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
Definition OcTreeBaseImpl.h:545
void expandRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
recursive call of expand()
Definition OcTreeBaseImpl.hxx:742
virtual void expand()
Expands all pruned nodes (reverse of prune())
Definition OcTreeBaseImpl.hxx:536
double resolution
in meters
Definition OcTreeBaseImpl.h:547
virtual size_t memoryUsageNode() const
Definition OcTreeBaseImpl.h:247
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
Definition OcTreeBaseImpl.hxx:1016
std::vector< KeyRay > keyrays
Definition OcTreeBaseImpl.h:562
std::ostream & writeData(std::ostream &s) const
Write complete state of tree to stream (without file header) unmodified. Pruning the tree first produ...
Definition OcTreeBaseImpl.hxx:763
virtual ~OcTreeBaseImpl()
Definition OcTreeBaseImpl.hxx:68
bool operator==(const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
Comparison between two octrees, all meta data, all nodes, and the structure must be identical.
Definition OcTreeBaseImpl.hxx:125
void swapContent(OcTreeBaseImpl< NODE, INTERFACE > &rhs)
Swap contents of two octrees, i.e., only the underlying pointer / tree structure.
Definition OcTreeBaseImpl.hxx:114
void deleteNodeChild(NODE *node, unsigned int childIdx)
Deletes the i-th child of the node.
Definition OcTreeBaseImpl.hxx:189
iterator begin(unsigned char maxDepth=0) const
Definition OcTreeBaseImpl.h:327
void pruneRecurs(ColorOcTreeNode *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
Definition OcTreeBaseImpl.hxx:719
unsigned long long memoryFullGrid() const
Definition OcTreeBaseImpl.hxx:850
void clear()
Deletes the complete tree structure.
Definition OcTreeBaseImpl.hxx:512
NODE * createNodeChild(NODE *node, unsigned int childIdx)
Creates (allocates) the i-th child of the node.
Definition OcTreeBaseImpl.hxx:173
double volume()
Definition OcTreeBaseImpl.hxx:1112
tree_iterator begin_tree(unsigned char maxDepth=0) const
Definition OcTreeBaseImpl.h:348
void calcNumNodesRecurs(NODE *node, size_t &num_nodes) const
Definition OcTreeBaseImpl.hxx:1026
void getUnknownLeafCenters(point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const
return centers of leafs that do NOT exist (but could) in a given bounding box
Definition OcTreeBaseImpl.hxx:1046
void init()
initialize non-trivial members, helper for constructors
Definition OcTreeBaseImpl.hxx:87
point3d tree_center
Definition OcTreeBaseImpl.h:554
virtual bool pruneNode(NODE *node)
Prunes a node when it is collapsible.
Definition OcTreeBaseImpl.hxx:267
double resolution_factor
= 1. / resolution
Definition OcTreeBaseImpl.h:548
bool computeRay(const point3d &origin, const point3d &end, std::vector< point3d > &ray)
Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the ...
Definition OcTreeBaseImpl.hxx:651
bool nodeHasChildren(const NODE *node) const
Safe test if node has any children.
Definition OcTreeBaseImpl.hxx:244
virtual size_t size() const
Definition OcTreeBaseImpl.h:241
virtual bool isNodeCollapsible(const NODE *node) const
A node is collapsible if all children exist, don't have children of their own and have the same occup...
Definition OcTreeBaseImpl.hxx:214
bool size_changed
Definition OcTreeBaseImpl.h:552
std::ostream & writeNodesRecurs(const NODE *, std::ostream &s) const
recursive call of writeData()
Definition OcTreeBaseImpl.hxx:771
NODE * search(double x, double y, double z, unsigned int depth=0) const
Search node at specified depth given a 3d point (depth=0: search full tree depth).
Definition OcTreeBaseImpl.hxx:421
size_t tree_size
number of nodes in tree flag to denote whether the octree extent changed (for lazy min/max eval)
Definition OcTreeBaseImpl.h:550
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
Definition OcTreeBaseImpl.hxx:1086
std::istream & readNodesRecurs(NODE *, std::istream &s)
recursive call of readData()
Definition OcTreeBaseImpl.hxx:824
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
Traces a ray from origin to end (excluding), returning an OcTreeKey of all nodes traversed by the bea...
Definition OcTreeBaseImpl.hxx:542
double getNodeSize(unsigned depth) const
Definition OcTreeBaseImpl.h:113
virtual void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
Definition OcTreeBaseImpl.hxx:872
std::vector< double > sizeLookupTable
Definition OcTreeBaseImpl.h:559
NODE * root
Pointer to the root NODE, NULL for empty tree.
Definition OcTreeBaseImpl.h:542
double min_value[3]
min in x, y, z contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl....
Definition OcTreeBaseImpl.h:557
void allocNodeChildren(NODE *node)
Definition OcTreeBaseImpl.hxx:286
OcTreeKey adjustKeyAtDepth(const OcTreeKey &key, unsigned int depth) const
Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)
Definition OcTreeBaseImpl.h:399
void calcMinMax()
recalculates min and max in x, y, z. Does nothing when tree size didn't change.
Definition OcTreeBaseImpl.hxx:900
OcTreeBaseImpl(double resolution)
Definition OcTreeBaseImpl.hxx:46
OcTreeKey is a container class for internal key addressing.
Definition OcTreeKey.h:70
float & x()
Definition Vector3.h:131
float & y()
Definition Vector3.h:136
float & z()
Definition Vector3.h:141
double norm() const
Definition Vector3.h:260
Namespace the OctoMap library and visualization tools.
uint16_t key_type
Definition OcTreeKey.h:63
std::list< octomath::Vector3 > point3d_list
Definition octomap_types.h:54
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition octomap_types.h:49
uint8_t computeChildIdx(const OcTreeKey &key, int depth)
generate child index (between 0 and 7) from key at given tree depth
Definition OcTreeKey.h:207
#define OCTOMAP_ERROR_STR(args)
Definition octomap_types.h:79
#define OCTOMAP_WARNING_STR(args)
Definition octomap_types.h:77