Skip to content

Commit

Permalink
search: add optional found_depth return by pointer
Browse files Browse the repository at this point in the history
Add an optional found_depth return by pointer. If the found_depth
pointer is set, the depth the search stopped at will be set to what
found_depth points to. This way the caller can determine if the search
ended at the requested depth if that is important to the caller.
  • Loading branch information
c-andy-martin committed Feb 1, 2024
1 parent c6e5dbd commit 4d2b0de
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 9 deletions.
9 changes: 6 additions & 3 deletions octomap/include/octomap/OcTreeBaseImpl.h
Original file line number Diff line number Diff line change
Expand Up @@ -183,23 +183,26 @@ namespace octomap {
/**
* Search node at specified depth given a 3d point (depth=0: search full tree depth).
* You need to check if the returned node is NULL, since it can be in unknown space.
* If the caller needs to know the found node depth, it can be returned by setting found_depth.
* @return pointer to node if found, NULL otherwise
*/
NODE* search(double x, double y, double z, unsigned int depth = 0) const;
NODE* search(double x, double y, double z, unsigned int depth = 0, unsigned int* found_depth = nullptr) const;

/**
* Search node at specified depth given a 3d point (depth=0: search full tree depth)
* You need to check if the returned node is NULL, since it can be in unknown space.
* If the caller needs to know the found node depth, it can be returned by setting found_depth.
* @return pointer to node if found, NULL otherwise
*/
NODE* search(const point3d& value, unsigned int depth = 0) const;
NODE* search(const point3d& value, unsigned int depth = 0, unsigned int* found_depth = nullptr) const;

/**
* Search a node at specified depth given an addressing key (depth=0: search full tree depth)
* You need to check if the returned node is NULL, since it can be in unknown space.
* If the caller needs to know the found node depth, it can be returned by setting found_depth.
* @return pointer to node if found, NULL otherwise
*/
NODE* search(const OcTreeKey& key, unsigned int depth = 0) const;
NODE* search(const OcTreeKey& key, unsigned int depth = 0, unsigned int* found_depth = nullptr) const;

/**
* Delete a node (if exists) given a 3d point. Will always
Expand Down
21 changes: 15 additions & 6 deletions octomap/include/octomap/OcTreeBaseImpl.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -472,33 +472,33 @@ namespace octomap {
}

template <class NODE,class I>
NODE* OcTreeBaseImpl<NODE,I>::search(const point3d& value, unsigned int depth) const {
NODE* OcTreeBaseImpl<NODE,I>::search(const point3d& value, unsigned int depth, unsigned int* found_depth) const {
OcTreeKey key;
if (!coordToKeyChecked(value, key)){
OCTOMAP_ERROR_STR("Error in search: ["<< value <<"] is out of OcTree bounds!");
return NULL;
}
else {
return this->search(key, depth);
return this->search(key, depth, found_depth);
}

}

template <class NODE,class I>
NODE* OcTreeBaseImpl<NODE,I>::search(double x, double y, double z, unsigned int depth) const {
NODE* OcTreeBaseImpl<NODE,I>::search(double x, double y, double z, unsigned int depth, unsigned int* found_depth) const {
OcTreeKey key;
if (!coordToKeyChecked(x, y, z, key)){
OCTOMAP_ERROR_STR("Error in search: ["<< x <<" "<< y << " " << z << "] is out of OcTree bounds!");
return NULL;
}
else {
return this->search(key, depth);
return this->search(key, depth, found_depth);
}
}


template <class NODE,class I>
NODE* OcTreeBaseImpl<NODE,I>::search (const OcTreeKey& key, unsigned int depth) const {
NODE* OcTreeBaseImpl<NODE,I>::search (const OcTreeKey& key, unsigned int depth, unsigned int* found_depth) const {
assert(depth <= tree_depth);
if (root == NULL)
return NULL;
Expand All @@ -517,9 +517,11 @@ namespace octomap {
NODE* curNode (root);

int diff = tree_depth - depth;
unsigned int current_depth = 0;

// follow nodes down to requested level (for diff = 0 it's the last level)
for (int i=(tree_depth-1); i>=diff; --i) {
for (int i=(tree_depth-1); i>=diff; --i, ++current_depth) {
assert(current_depth < depth);
unsigned int pos = computeChildIdx(key_at_depth, i);
if (nodeChildExists(curNode, pos)) {
// cast needed: (nodes need to ensure it's the right pointer)
Expand All @@ -528,13 +530,20 @@ namespace octomap {
// we expected a child but did not get it
// is the current node a leaf already?
if (!nodeHasChildren(curNode)) { // TODO similar check to nodeChildExists?
if (found_depth) {
*found_depth = current_depth;
}
return curNode;
} else {
// it is not, search failed
return NULL;
}
}
} // end for
assert(current_depth == depth);
if (found_depth) {
*found_depth = current_depth;
}
return curNode;
}

Expand Down

0 comments on commit 4d2b0de

Please sign in to comment.