45 template <
class NODE,
class I>
47 I(), root(NULL), tree_depth(16), tree_max_val(32768),
48 resolution(in_resolution), tree_size(0)
56 template <
class NODE,
class I>
58 I(), root(NULL), tree_depth(in_tree_depth), tree_max_val(in_tree_max_val),
59 resolution(in_resolution), tree_size(0)
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)
82 root =
new NODE(*(rhs.
root));
86 template <
class NODE,
class I>
89 this->setResolution(this->resolution);
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());
108 this->keyrays.resize(1);
113 template <
class NODE,
class I>
115 NODE* this_root = root;
117 other.
root = this_root;
119 size_t this_size = this->tree_size;
124 template <
class NODE,
class I>
137 for (; it != end; ++it, ++other_it){
138 if (other_it == other_end)
141 if (it.getDepth() != other_it.getDepth()
142 || it.getKey() != other_it.getKey()
143 || !(*it == *other_it))
149 if (other_it != other_end)
155 template <
class NODE,
class I>
158 resolution_factor = 1. / resolution;
160 tree_center(0) = tree_center(1) = tree_center(2)
161 = (float) (((
double) tree_max_val) / resolution_factor);
164 sizeLookupTable.resize(tree_depth+1);
165 for(
unsigned i = 0; i <= tree_depth; ++i){
166 sizeLookupTable[i] = resolution * double(1 << (tree_depth - i));
172 template <
class NODE,
class I>
174 assert(childIdx < 8);
175 if (node->children == NULL) {
176 allocNodeChildren(node);
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>
217 if (!nodeChildExists(node, 0))
220 const NODE* firstChild = getNodeChild(node, 0);
221 if (nodeHasChildren(firstChild))
224 for (
unsigned int i = 1; i<8; i++) {
227 if (!nodeChildExists(node, i) || nodeHasChildren(getNodeChild(node, i)) || !(*(getNodeChild(node, i)) == *(firstChild)))
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>
258 assert(!nodeHasChildren(node));
260 for (
unsigned int k=0; k<8; k++) {
261 NODE* newNode = createNodeChild(node, k);
262 newNode->copyData(*node);
266 template <
class NODE,
class I>
269 if (!isNodeCollapsible(node))
273 node->copyData(*(getNodeChild(node, 0)));
276 for (
unsigned int i=0;i<8;i++) {
277 deleteNodeChild(node, 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>
298 assert (depth <= tree_depth);
299 int keyval = ((int) floor(resolution_factor * coordinate));
301 unsigned int diff = tree_depth - depth;
303 return keyval + tree_max_val;
305 return ((keyval >> diff) << diff) + (1 << (diff-1)) + tree_max_val;
309 template <
class NODE,
class I>
313 int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val;
316 if (( scaled_coord >= 0) && (((
unsigned int) scaled_coord) < (2*tree_max_val))) {
317 keyval = scaled_coord;
324 template <
class NODE,
class I>
328 int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val;
331 if (( scaled_coord >= 0) && (((
unsigned int) scaled_coord) < (2*tree_max_val))) {
332 keyval = scaled_coord;
333 keyval = adjustKeyAtDepth(keyval, depth);
339 template <
class NODE,
class I>
342 for (
unsigned int i=0;i<3;i++) {
343 if (!coordToKeyChecked( point(i), key[i]))
return false;
348 template <
class NODE,
class I>
351 for (
unsigned int i=0;i<3;i++) {
352 if (!coordToKeyChecked( point(i), depth, key[i]))
return false;
357 template <
class NODE,
class I>
360 if (!(coordToKeyChecked(x, key[0])
361 && coordToKeyChecked(y, key[1])
362 && coordToKeyChecked(z, key[2])))
370 template <
class NODE,
class I>
373 if (!(coordToKeyChecked(x, depth, key[0])
374 && coordToKeyChecked(y, depth, key[1])
375 && coordToKeyChecked(z, depth, key[2])))
383 template <
class NODE,
class I>
385 unsigned int diff = tree_depth - depth;
390 return (((key-tree_max_val) >> diff) << diff) + (1 << (diff-1)) + tree_max_val;
393 template <
class NODE,
class I>
395 assert(depth <= tree_depth);
400 }
else if (depth == tree_depth) {
401 return keyToCoord(key);
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>
410 if (!coordToKeyChecked(value, key)){
415 return this->search(key, depth);
420 template <
class NODE,
class I>
423 if (!coordToKeyChecked(x, y, z, key)){
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>
435 assert(depth <= tree_depth);
446 if (depth != tree_depth)
447 key_at_depth = adjustKeyAtDepth(key, depth);
449 NODE* curNode (root);
451 int diff = tree_depth - depth;
454 for (
int i=(tree_depth-1); i>=diff; --i) {
456 if (nodeChildExists(curNode, pos)) {
458 curNode = getNodeChild(curNode, pos);
462 if (!nodeHasChildren(curNode)) {
474 template <
class NODE,
class I>
477 if (!coordToKeyChecked(value, key)){
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>
490 if (!coordToKeyChecked(x, y, z, key)){
491 OCTOMAP_ERROR_STR(
"Error in deleteNode: ["<< x <<
" "<< y <<
" " << z <<
"] is out of OcTree bounds!");
495 return this->deleteNode(key, depth);
500 template <
class NODE,
class I>
508 return deleteNodeRecurs(root, 0, depth, key);
511 template <
class NODE,
class I>
514 deleteNodeRecurs(root);
518 this->size_changed =
true;
522 template <
class NODE,
class I>
527 for (
unsigned int depth=tree_depth-1; depth > 0; --depth) {
528 unsigned int num_pruned = 0;
529 pruneRecurs(this->root, 0, depth, num_pruned);
535 template <
class NODE,
class I>
538 expandRecurs(root,0, tree_depth);
541 template <
class NODE,
class I>
555 << origin <<
" -> " << end <<
") out of bounds in computeRayKeys");
560 if (key_origin == key_end)
567 point3d direction = (end - origin);
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) {
654 if (!computeRayKeys(origin, end, keyrays.at(0)))
return false;
656 _ray.push_back(keyToCoord(*it));
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){
669 this->deleteNodeRecurs(
static_cast<NODE*
>(node->children[i]));
672 delete[] node->children;
673 node->children = NULL;
680 template <
class NODE,
class I>
682 if (depth >= max_depth)
689 if (!nodeChildExists(node, pos)) {
691 if ((!nodeHasChildren(node)) && (node != this->root)) {
702 bool deleteChild = deleteNodeRecurs(getNodeChild(node, pos), depth+1, max_depth, key);
706 this->deleteNodeChild(node, pos);
708 if (!nodeHasChildren(node))
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++) {
726 if (nodeChildExists(node, i)) {
727 pruneRecurs(getNodeChild(node, i), depth+1, max_depth, num_pruned);
734 if (pruneNode(node)) {
741 template <
class NODE,
class I>
743 unsigned int max_depth) {
744 if (depth >= max_depth)
750 if (!nodeHasChildren(node)){
754 for (
unsigned int i=0; i<8; i++) {
755 if (nodeChildExists(node, i)) {
756 expandRecurs(getNodeChild(node, i), depth+1, max_depth);
762 template <
class NODE,
class I>
765 writeNodesRecurs(root, s);
770 template <
class NODE,
class I>
775 std::bitset<8> children;
776 for (
unsigned int i=0; i<8; i++) {
777 if (nodeChildExists(node, 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) {
793 this->writeNodesRecurs(getNodeChild(node, i), s);
800 template <
class NODE,
class I>
804 OCTOMAP_WARNING_STR(__FILE__ <<
":" << __LINE__ <<
"Warning: Input filestream not \"good\"");
817 readNodesRecurs(root, s);
819 tree_size = calcNumNodes();
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){
838 NODE* newNode = createNodeChild(node, i);
839 readNodesRecurs(newNode, s);
849 template <
class NODE,
class I>
854 double size_x, size_y, size_z;
855 this->getMetricSize(size_x, size_y,size_z);
862 return (
unsigned long long)((size_x/resolution) * (size_y/resolution) * (size_z/resolution)
863 *
sizeof(root->getValue()));
871 template <
class NODE,
class I>
874 double minX, minY, minZ;
875 double maxX, maxY, maxZ;
877 getMetricMax(maxX, maxY, maxZ);
878 getMetricMin(minX, minY, minZ);
885 template <
class NODE,
class I>
888 double minX, minY, minZ;
889 double maxX, maxY, maxZ;
891 getMetricMax(maxX, maxY, maxZ);
892 getMetricMin(minX, minY, minZ);
899 template <
class NODE,
class I>
906 min_value[0] = min_value[1] = min_value[2] = 0.0;
907 max_value[0] = max_value[1] = max_value[2] = 0.0;
908 size_changed =
false;
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)
920 double size = it.getSize();
921 double halfSize = size/2.0;
922 double x = it.getX() - halfSize;
923 double y = it.getY() - halfSize;
924 double z = it.getZ() - halfSize;
925 if (x < min_value[0]) min_value[0] = x;
926 if (y < min_value[1]) min_value[1] = y;
927 if (z < min_value[2]) min_value[2] = z;
932 if (x > max_value[0]) max_value[0] = x;
933 if (y > max_value[1]) max_value[1] = y;
934 if (z > max_value[2]) max_value[2] = z;
938 size_changed =
false;
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>
1020 calcNumNodesRecurs(root, retval);
1025 template <
class NODE,
class I>
1028 if (nodeHasChildren(node)) {
1029 for (
unsigned int i=0; i<8; ++i) {
1030 if (nodeChildExists(node, i)) {
1032 calcNumNodesRecurs(getNodeChild(node, i), num_nodes);
1038 template <
class NODE,
class I>
1040 size_t num_leaf_nodes = this->getNumLeafNodes();
1041 size_t num_inner_nodes = tree_size - num_leaf_nodes;
1042 return (
sizeof(
OcTreeBaseImpl<NODE,I>) + memoryUsageNode() * tree_size + num_inner_nodes *
sizeof(NODE*[8]));
1045 template <
class NODE,
class I>
1048 assert(depth <= tree_depth);
1052 point3d pmin_clamped = this->keyToCoord(this->coordToKey(pmin, depth), depth);
1053 point3d pmax_clamped = this->keyToCoord(this->coordToKey(pmax, depth), depth);
1056 unsigned int steps[3];
1057 float step_size = this->resolution * pow(2, tree_depth-depth);
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>
1090 return getNumLeafNodesRecurs(root);
1094 template <
class NODE,
class I>
1098 if (!nodeHasChildren(parent))
1101 size_t sum_leafs_children = 0;
1102 for (
unsigned int i=0; i<8; ++i) {
1103 if (nodeChildExists(parent, i)) {
1104 sum_leafs_children += getNumLeafNodesRecurs(getNodeChild(parent, i));
1107 return sum_leafs_children;
1111 template <
class NODE,
class I>
1114 getMetricSize(x, y, z);