@@ -472,33 +472,33 @@ namespace octomap {
472
472
}
473
473
474
474
template <class NODE ,class I >
475
- NODE* OcTreeBaseImpl<NODE,I>::search(const point3d& value, unsigned int depth) const {
475
+ NODE* OcTreeBaseImpl<NODE,I>::search(const point3d& value, unsigned int depth, unsigned int * found_depth ) const {
476
476
OcTreeKey key;
477
477
if (!coordToKeyChecked (value, key)){
478
478
OCTOMAP_ERROR_STR (" Error in search: [" << value <<" ] is out of OcTree bounds!" );
479
479
return NULL ;
480
480
}
481
481
else {
482
- return this ->search (key, depth);
482
+ return this ->search (key, depth, found_depth );
483
483
}
484
484
485
485
}
486
486
487
487
template <class NODE ,class I >
488
- NODE* OcTreeBaseImpl<NODE,I>::search(double x, double y, double z, unsigned int depth) const {
488
+ NODE* OcTreeBaseImpl<NODE,I>::search(double x, double y, double z, unsigned int depth, unsigned int * found_depth ) const {
489
489
OcTreeKey key;
490
490
if (!coordToKeyChecked (x, y, z, key)){
491
491
OCTOMAP_ERROR_STR (" Error in search: [" << x <<" " << y << " " << z << " ] is out of OcTree bounds!" );
492
492
return NULL ;
493
493
}
494
494
else {
495
- return this ->search (key, depth);
495
+ return this ->search (key, depth, found_depth );
496
496
}
497
497
}
498
498
499
499
500
500
template <class NODE ,class I >
501
- NODE* OcTreeBaseImpl<NODE,I>::search (const OcTreeKey& key, unsigned int depth) const {
501
+ NODE* OcTreeBaseImpl<NODE,I>::search (const OcTreeKey& key, unsigned int depth, unsigned int * found_depth ) const {
502
502
assert (depth <= tree_depth);
503
503
if (root == NULL )
504
504
return NULL ;
@@ -517,9 +517,11 @@ namespace octomap {
517
517
NODE* curNode (root);
518
518
519
519
int diff = tree_depth - depth;
520
+ unsigned int current_depth = 0 ;
520
521
521
522
// follow nodes down to requested level (for diff = 0 it's the last level)
522
- for (int i=(tree_depth-1 ); i>=diff; --i) {
523
+ for (int i=(tree_depth-1 ); i>=diff; --i, ++current_depth) {
524
+ assert (current_depth < depth);
523
525
unsigned int pos = computeChildIdx (key_at_depth, i);
524
526
if (nodeChildExists (curNode, pos)) {
525
527
// cast needed: (nodes need to ensure it's the right pointer)
@@ -528,13 +530,20 @@ namespace octomap {
528
530
// we expected a child but did not get it
529
531
// is the current node a leaf already?
530
532
if (!nodeHasChildren (curNode)) { // TODO similar check to nodeChildExists?
533
+ if (found_depth) {
534
+ *found_depth = current_depth;
535
+ }
531
536
return curNode;
532
537
} else {
533
538
// it is not, search failed
534
539
return NULL ;
535
540
}
536
541
}
537
542
} // end for
543
+ assert (current_depth == depth);
544
+ if (found_depth) {
545
+ *found_depth = current_depth;
546
+ }
538
547
return curNode;
539
548
}
540
549
0 commit comments