octomap 1.5.0
|
00001 // $Id: OcTreeBaseImpl.hxx 417 2012-08-27 13:02:40Z ahornung $ 00002 00011 /* 00012 * Copyright (c) 2009-2011, K. M. Wurm, A. Hornung, University of Freiburg 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in the 00022 * documentation and/or other materials provided with the distribution. 00023 * * Neither the name of the University of Freiburg nor the names of its 00024 * contributors may be used to endorse or promote products derived from 00025 * this software without specific prior written permission. 00026 * 00027 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 */ 00039 00040 #undef max 00041 #undef min 00042 #include <limits> 00043 00044 namespace octomap { 00045 00046 00047 template <class NODE,class I> 00048 OcTreeBaseImpl<NODE,I>::OcTreeBaseImpl(double resolution) : 00049 I(), root(NULL), tree_depth(16), tree_max_val(32768), 00050 resolution(resolution), tree_size(0) 00051 { 00052 00053 this->setResolution(resolution); 00054 for (unsigned i = 0; i< 3; i++){ 00055 max_value[i] = -(std::numeric_limits<double>::max( )); 00056 min_value[i] = std::numeric_limits<double>::max( ); 00057 } 00058 size_changed = true; 00059 00060 // init root node: 00061 root = new NODE(); 00062 tree_size++; 00063 } 00064 00065 template <class NODE,class I> 00066 OcTreeBaseImpl<NODE,I>::OcTreeBaseImpl(double resolution, unsigned int tree_depth, unsigned int tree_max_val) : 00067 I(), root(NULL), tree_depth(tree_depth), tree_max_val(tree_max_val), 00068 resolution(resolution), tree_size(0) 00069 { 00070 this->setResolution(resolution); 00071 for (unsigned i = 0; i< 3; i++){ 00072 max_value[i] = -(std::numeric_limits<double>::max( )); 00073 min_value[i] = std::numeric_limits<double>::max( ); 00074 } 00075 size_changed = true; 00076 00077 // init root node: 00078 root = new NODE(); 00079 tree_size++; 00080 } 00081 00082 00083 template <class NODE,class I> 00084 OcTreeBaseImpl<NODE,I>::~OcTreeBaseImpl(){ 00085 delete root; 00086 } 00087 00088 00089 template <class NODE,class I> 00090 OcTreeBaseImpl<NODE,I>::OcTreeBaseImpl(const OcTreeBaseImpl<NODE,I>& rhs) : 00091 root(NULL), tree_depth(rhs.tree_depth), tree_max_val(rhs.tree_max_val), 00092 resolution(rhs.resolution), tree_size(rhs.tree_size) 00093 { 00094 this->setResolution(resolution); 00095 for (unsigned i = 0; i< 3; i++){ 00096 max_value[i] = rhs.max_value[i]; 00097 min_value[i] = rhs.min_value[i]; 00098 } 00099 00100 // copy nodes recursively: 00101 root = new NODE(*(rhs.root)); 00102 00103 00104 } 00105 00106 template <class NODE,class I> 00107 bool OcTreeBaseImpl<NODE,I>::operator== (const OcTreeBaseImpl<NODE,I>& other) const{ 00108 if (tree_depth != other.tree_depth || tree_max_val != other.tree_max_val 00109 || resolution != other.resolution || tree_size != other.tree_size){ 00110 return false; 00111 } 00112 00113 // traverse all nodes, check if structure the same 00114 OcTreeBaseImpl<NODE,I>::tree_iterator it = this->begin_tree(); 00115 OcTreeBaseImpl<NODE,I>::tree_iterator end = this->end_tree(); 00116 OcTreeBaseImpl<NODE,I>::tree_iterator other_it = other.begin_tree(); 00117 OcTreeBaseImpl<NODE,I>::tree_iterator other_end = other.end_tree(); 00118 00119 for (; it != end; ++it, ++other_it){ 00120 if (other_it == other_end) 00121 return false; 00122 00123 if (it.getDepth() != other_it.getDepth() 00124 || it.getKey() != other_it.getKey() 00125 || !(*it == *other_it)) 00126 { 00127 return false; 00128 } 00129 } 00130 00131 if (other_it != other_end) 00132 return false; 00133 00134 return true; 00135 } 00136 00137 template <class NODE,class I> 00138 void OcTreeBaseImpl<NODE,I>::setResolution(double r) { 00139 resolution = r; 00140 resolution_factor = 1. / resolution; 00141 00142 tree_center(0) = tree_center(1) = tree_center(2) 00143 = (float) (((double) tree_max_val) / resolution_factor); 00144 00145 // init node size lookup table: 00146 sizeLookupTable.resize(tree_depth+1); 00147 for(unsigned i = 0; i <= tree_depth; ++i){ 00148 sizeLookupTable[i] = resolution * double(1 << (tree_depth - i)); 00149 } 00150 00151 size_changed = true; 00152 } 00153 00154 template <class NODE,class I> 00155 inline unsigned short int OcTreeBaseImpl<NODE,I>::coordToKey(double coordinate, unsigned depth) const{ 00156 assert (depth <= tree_depth); 00157 int keyval = ((int) floor(resolution_factor * coordinate)); 00158 00159 unsigned int diff = tree_depth - depth; 00160 if(!diff) // same as coordToKey without depth 00161 return keyval + tree_max_val; 00162 else // shift right and left => erase last bits. Then add offset. 00163 return ((keyval >> diff) << diff) + (1 << (diff-1)) + tree_max_val; 00164 } 00165 00166 00167 template <class NODE,class I> 00168 bool OcTreeBaseImpl<NODE,I>::coordToKeyChecked(double coordinate, unsigned short int& keyval) const { 00169 00170 // scale to resolution and shift center for tree_max_val 00171 int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val; 00172 00173 // keyval within range of tree? 00174 if (( scaled_coord >= 0) && (((unsigned int) scaled_coord) < (2*tree_max_val))) { 00175 keyval = scaled_coord; 00176 return true; 00177 } 00178 return false; 00179 } 00180 00181 00182 template <class NODE,class I> 00183 bool OcTreeBaseImpl<NODE,I>::coordToKeyChecked(double coordinate, unsigned depth, unsigned short int& keyval) const { 00184 00185 // scale to resolution and shift center for tree_max_val 00186 int scaled_coord = ((int) floor(resolution_factor * coordinate)) + tree_max_val; 00187 00188 // keyval within range of tree? 00189 if (( scaled_coord >= 0) && (((unsigned int) scaled_coord) < (2*tree_max_val))) { 00190 keyval = scaled_coord; 00191 keyval = adjustKeyAtDepth(keyval, depth); 00192 return true; 00193 } 00194 return false; 00195 } 00196 00197 template <class NODE,class I> 00198 bool OcTreeBaseImpl<NODE,I>::coordToKeyChecked(const point3d& point, OcTreeKey& key) const{ 00199 00200 for (unsigned int i=0;i<3;i++) { 00201 if (!coordToKeyChecked( point(i), key[i])) return false; 00202 } 00203 return true; 00204 } 00205 00206 template <class NODE,class I> 00207 bool OcTreeBaseImpl<NODE,I>::coordToKeyChecked(const point3d& point, unsigned depth, OcTreeKey& key) const{ 00208 00209 for (unsigned int i=0;i<3;i++) { 00210 if (!coordToKeyChecked( point(i), depth, key[i])) return false; 00211 } 00212 return true; 00213 } 00214 00215 template <class NODE,class I> 00216 unsigned short int OcTreeBaseImpl<NODE,I>::adjustKeyAtDepth(unsigned short int key, unsigned int depth) const{ 00217 unsigned int diff = tree_depth - depth; 00218 00219 if(diff == 0) 00220 return key; 00221 else 00222 return (((key-tree_max_val) >> diff) << diff) + (1 << (diff-1)) + tree_max_val; 00223 } 00224 00225 template <class NODE,class I> 00226 double OcTreeBaseImpl<NODE,I>::keyToCoord(unsigned short int key, unsigned depth) const{ 00227 assert(depth <= tree_depth); 00228 00229 // root is centered on 0 = 0.0 00230 if (depth == 0) { 00231 return 0.0; 00232 } else if (depth == tree_depth) { 00233 return keyToCoord(key); 00234 } else { 00235 return (floor( (double(key)-double(this->tree_max_val)) /double(1 << (tree_depth - depth)) ) + 0.5 ) * this->getNodeSize(depth); 00236 } 00237 } 00238 00239 template <class NODE,class I> 00240 bool OcTreeBaseImpl<NODE,I>::genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) const { 00241 00242 if (keyval >= 2*tree_max_val) 00243 return false; 00244 00245 unsigned int diff = tree_depth - depth; 00246 if(!diff) { 00247 out_keyval = keyval; 00248 } 00249 else { 00250 out_keyval = (((keyval-tree_max_val) >> diff) << diff) + (1 << (diff-1)) + tree_max_val; 00251 } 00252 return true; 00253 } 00254 00255 template <class NODE,class I> 00256 bool OcTreeBaseImpl<NODE,I>::genKeyAtDepth(const OcTreeKey& key, unsigned int depth, OcTreeKey& out_key) const { 00257 for (unsigned int i=0;i<3;i++) { 00258 if (!genKeyValueAtDepth( key[i], depth, out_key[i])) return false; 00259 } 00260 return true; 00261 } 00262 00263 template <class NODE,class I> 00264 NODE* OcTreeBaseImpl<NODE,I>::search(const point3d& value, unsigned int depth) const { 00265 00266 // Search is a variant of insert which aborts if 00267 // it had to insert nodes 00268 00269 OcTreeKey key; 00270 if (!coordToKeyChecked(value, key)){ 00271 OCTOMAP_ERROR_STR("Error in search: ["<< value <<"] is out of OcTree bounds!"); 00272 return NULL; 00273 } 00274 else { 00275 return this->search(key, depth); 00276 } 00277 00278 } 00279 00280 template <class NODE,class I> 00281 NODE* OcTreeBaseImpl<NODE,I>::search(float x, float y, float z, unsigned int depth) const { 00282 return this->search(point3d(x,y,z), depth); 00283 } 00284 00285 00286 template <class NODE,class I> 00287 NODE* OcTreeBaseImpl<NODE,I>::search (const OcTreeKey& key, unsigned int depth) const { 00288 assert(depth <= tree_depth); 00289 00290 if (depth == 0) 00291 depth = tree_depth; 00292 00293 00294 00295 // generate appropriate key_at_depth for queried depth 00296 OcTreeKey key_at_depth = key; 00297 if (depth != tree_depth) 00298 key_at_depth = adjustKeyAtDepth(key, depth); 00299 00300 NODE* curNode (root); 00301 00302 unsigned int diff = tree_depth - depth; 00303 00304 // follow nodes down to requested level (for diff = 0 it's the last level) 00305 for (unsigned i=(tree_depth-1); i>=diff; --i) { 00306 unsigned int pos = computeChildIdx(key_at_depth, i); 00307 if (curNode->childExists(pos)) { 00308 // cast needed: (nodes need to ensure it's the right pointer) 00309 curNode = static_cast<NODE*>( curNode->getChild(pos) ); 00310 } else { 00311 // we expected a child but did not get it 00312 // is the current node a leaf already? 00313 if (!curNode->hasChildren()) { 00314 return curNode; 00315 } else { 00316 // it is not, search failed 00317 return NULL; 00318 } 00319 } 00320 } // end for 00321 return curNode; 00322 } 00323 00324 00325 template <class NODE,class I> 00326 bool OcTreeBaseImpl<NODE,I>::deleteNode(const point3d& value, unsigned int depth) { 00327 OcTreeKey key; 00328 if (!coordToKeyChecked(value, key)){ 00329 OCTOMAP_ERROR_STR("Error in deleteNode: ["<< value <<"] is out of OcTree bounds!"); 00330 return false; 00331 } 00332 else { 00333 return this->deleteNode(key, depth); 00334 } 00335 00336 } 00337 00338 template <class NODE,class I> 00339 bool OcTreeBaseImpl<NODE,I>::deleteNode(float x, float y, float z, unsigned int depth) { 00340 return this->deleteNode(point3d(x,y,z), depth); 00341 } 00342 00343 00344 template <class NODE,class I> 00345 bool OcTreeBaseImpl<NODE,I>::deleteNode(const OcTreeKey& key, unsigned int depth) { 00346 if (depth == 0) 00347 depth = tree_depth; 00348 00349 return deleteNodeRecurs(root, 0, depth, key); 00350 } 00351 00352 template <class NODE,class I> 00353 void OcTreeBaseImpl<NODE,I>::clear() { 00354 // don't clear if the tree is empty: 00355 if (this->root->hasChildren()) { 00356 delete this->root; 00357 this->root = new NODE(); 00358 } 00359 this->tree_size = 1; 00360 // max extent of tree changed: 00361 this->size_changed = true; 00362 } 00363 00364 00365 template <class NODE,class I> 00366 void OcTreeBaseImpl<NODE,I>::prune() { 00367 for (unsigned int depth=tree_depth-1; depth>0; depth--) { 00368 unsigned int num_pruned = 0; 00369 pruneRecurs(this->root, 0, depth, num_pruned); 00370 if (num_pruned == 0) break; 00371 } 00372 } 00373 00374 template <class NODE,class I> 00375 void OcTreeBaseImpl<NODE,I>::expand() { 00376 expandRecurs(root,0, tree_depth); 00377 } 00378 00379 template <class NODE,class I> 00380 bool OcTreeBaseImpl<NODE,I>::computeRayKeys(const point3d& origin, 00381 const point3d& end, 00382 KeyRay& ray) const { 00383 00384 // see "A Faster Voxel Traversal Algorithm for Ray Tracing" by Amanatides & Woo 00385 // basically: DDA in 3D 00386 00387 ray.reset(); 00388 00389 OcTreeKey key_origin, key_end; 00390 if ( !OcTreeBaseImpl<NODE,I>::coordToKeyChecked(origin, key_origin) || 00391 !OcTreeBaseImpl<NODE,I>::coordToKeyChecked(end, key_end) ) { 00392 OCTOMAP_WARNING_STR("coordinates ( " 00393 << origin << " -> " << end << ") out of bounds in computeRayKeys"); 00394 return false; 00395 } 00396 00397 00398 if (key_origin == key_end) return true; // same tree cell, we're done. 00399 00400 ray.addKey(key_origin); 00401 00402 // Initialization phase ------------------------------------------------------- 00403 00404 point3d direction = (end - origin); 00405 float length = (float) direction.norm(); 00406 direction /= length; // normalize vector 00407 00408 int step[3]; 00409 double tMax[3]; 00410 double tDelta[3]; 00411 00412 OcTreeKey current_key = key_origin; 00413 00414 for(unsigned int i=0; i < 3; ++i) { 00415 // compute step direction 00416 if (direction(i) > 0.0) step[i] = 1; 00417 else if (direction(i) < 0.0) step[i] = -1; 00418 else step[i] = 0; 00419 00420 // compute tMax, tDelta 00421 if (step[i] != 0) { 00422 // corner point of voxel (in direction of ray) 00423 double voxelBorder = this->keyToCoord(current_key[i]); 00424 voxelBorder += (float) (step[i] * this->resolution * 0.5); 00425 00426 tMax[i] = ( voxelBorder - origin(i) ) / direction(i); 00427 tDelta[i] = this->resolution / fabs( direction(i) ); 00428 } 00429 else { 00430 tMax[i] = std::numeric_limits<double>::max( ); 00431 tDelta[i] = std::numeric_limits<double>::max( ); 00432 } 00433 } 00434 00435 // for speedup: 00436 point3d origin_scaled = origin; 00437 origin_scaled /= (float) this->resolution; 00438 double length_scaled = length - this->resolution/4.; // safety margin 00439 length_scaled /= this->resolution; // scale 00440 length_scaled = length_scaled*length_scaled; // avoid sqrt in dist comp. 00441 00442 // Incremental phase --------------------------------------------------------- 00443 00444 bool done = false; 00445 while (!done) { 00446 00447 unsigned int dim; 00448 00449 // find minimum tMax: 00450 if (tMax[0] < tMax[1]){ 00451 if (tMax[0] < tMax[2]) dim = 0; 00452 else dim = 2; 00453 } 00454 else { 00455 if (tMax[1] < tMax[2]) dim = 1; 00456 else dim = 2; 00457 } 00458 00459 // advance in direction "dim" 00460 current_key[dim] += step[dim]; 00461 tMax[dim] += tDelta[dim]; 00462 00463 assert (current_key[dim] < 2*this->tree_max_val); 00464 00465 // reached endpoint, key equv? 00466 if (current_key == key_end) { 00467 done = true; 00468 break; 00469 } 00470 else { 00471 00472 // reached endpoint world coords? 00473 double dist_from_origin = 0; 00474 for (unsigned int j = 0; j < 3; j++) { 00475 double coord = (double) current_key[j] - (double) this->tree_max_val; 00476 dist_from_origin += (coord - origin_scaled(j)) * (coord - origin_scaled(j)); 00477 } 00478 if (dist_from_origin > length_scaled) { 00479 done = true; 00480 break; 00481 } 00482 00483 else { // continue to add freespace cells 00484 ray.addKey(current_key); 00485 } 00486 } 00487 00488 assert ( ray.size() < ray.sizeMax() - 1); 00489 00490 } // end while 00491 00492 return true; 00493 } 00494 00495 template <class NODE,class I> 00496 bool OcTreeBaseImpl<NODE,I>::computeRay(const point3d& origin, const point3d& end, 00497 std::vector<point3d>& _ray) { 00498 _ray.clear(); 00499 if (!computeRayKeys(origin, end, keyray)) return false; 00500 for (KeyRay::const_iterator it = keyray.begin(); it != keyray.end(); ++it) { 00501 _ray.push_back(keyToCoord(*it)); 00502 } 00503 return true; 00504 } 00505 00506 template <class NODE,class I> 00507 bool OcTreeBaseImpl<NODE,I>::deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key){ 00508 if (depth >= max_depth) // on last level: delete child when going up 00509 return true; 00510 00511 unsigned int pos = computeChildIdx(key, this->tree_depth-1-depth); 00512 00513 if (!node->childExists(pos)) { 00514 // child does not exist, but maybe it's a pruned node? 00515 if ((!node->hasChildren()) && (node != this->root)) { 00516 // current node does not have children AND it's not the root node 00517 // -> expand pruned node 00518 node->expandNode(); 00519 this->tree_size+=8; 00520 this->size_changed = true; 00521 } else { // no branch here, node does not exist 00522 return false; 00523 } 00524 } 00525 00526 // follow down further, fix inner nodes on way back up 00527 bool deleteChild = deleteNodeRecurs(node->getChild(pos), depth+1, max_depth, key); 00528 if (deleteChild){ 00529 // TODO: lazy eval? 00530 node->deleteChild(pos); 00531 this->tree_size-=1; 00532 this->size_changed = true; 00533 if (!node->hasChildren()) 00534 return true; 00535 else{ 00536 node->updateOccupancyChildren(); 00537 } 00538 } 00539 // node did not lose a child, or still has other children 00540 return false; 00541 00542 } 00543 00544 template <class NODE,class I> 00545 void OcTreeBaseImpl<NODE,I>::pruneRecurs(NODE* node, unsigned int depth, 00546 unsigned int max_depth, unsigned int& num_pruned) { 00547 00548 if (depth < max_depth) { 00549 for (unsigned int i=0; i<8; i++) { 00550 if (node->childExists(i)) { 00551 pruneRecurs(node->getChild(i), depth+1, max_depth, num_pruned); 00552 } 00553 } 00554 } // end if depth 00555 00556 else { 00557 // max level reached 00558 if (node->pruneNode()) { 00559 num_pruned++; 00560 tree_size -= 8; 00561 size_changed = true; 00562 } 00563 } 00564 } 00565 00566 00567 template <class NODE,class I> 00568 void OcTreeBaseImpl<NODE,I>::expandRecurs(NODE* node, unsigned int depth, 00569 unsigned int max_depth) { 00570 if (depth >= max_depth) return; 00571 00572 // current node has no children => can be expanded 00573 if (!node->hasChildren()){ 00574 node->expandNode(); 00575 tree_size +=8; 00576 size_changed = true; 00577 } 00578 // recursively expand children 00579 for (unsigned int i=0; i<8; i++) { 00580 if (node->childExists(i)) { 00581 expandRecurs(node->getChild(i), depth+1, max_depth); 00582 } 00583 } 00584 } 00585 00586 00587 template <class NODE,class I> 00588 std::ostream& OcTreeBaseImpl<NODE,I>::writeData(std::ostream &s) const{ 00589 root->writeValue(s); 00590 return s; 00591 } 00592 00593 template <class NODE,class I> 00594 std::istream& OcTreeBaseImpl<NODE,I>::readData(std::istream &s) { 00595 00596 if (!s.good()){ 00597 OCTOMAP_WARNING_STR(__FILE__ << ":" << __LINE__ << "Warning: Input filestream not \"good\""); 00598 } 00599 00600 this->tree_size = 0; 00601 size_changed = true; 00602 00603 // tree needs to be newly created or cleared externally! 00604 if (root->hasChildren()) { 00605 OCTOMAP_ERROR_STR("Trying to read into an existing tree."); 00606 return s; 00607 } 00608 00609 root->readValue(s); 00610 tree_size = calcNumNodes(); // compute number of nodes 00611 return s; 00612 } 00613 00614 00615 00616 00617 template <class NODE,class I> 00618 size_t OcTreeBaseImpl<NODE,I>::memoryFullGrid() { 00619 double size_x, size_y, size_z; 00620 getMetricSize(size_x, size_y,size_z); 00621 00622 // assuming best case (one big array and efficient addressing) 00623 return (size_t) (ceil(resolution_factor * (double) size_x) * //sizeof (unsigned int*) * 00624 ceil(resolution_factor * (double) size_y) * //sizeof (unsigned int*) * 00625 ceil(resolution_factor * (double) size_z)) * 00626 sizeof(root->getValue()); 00627 00628 } 00629 00630 00631 // non-const versions, 00632 // change min/max/size_changed members 00633 00634 template <class NODE,class I> 00635 void OcTreeBaseImpl<NODE,I>::getMetricSize(double& x, double& y, double& z){ 00636 00637 double minX, minY, minZ; 00638 double maxX, maxY, maxZ; 00639 00640 getMetricMax(maxX, maxY, maxZ); 00641 getMetricMin(minX, minY, minZ); 00642 00643 x = maxX - minX; 00644 y = maxY - minY; 00645 z = maxZ - minZ; 00646 } 00647 00648 template <class NODE,class I> 00649 void OcTreeBaseImpl<NODE,I>::calcMinMax() { 00650 if (!size_changed) 00651 return; 00652 00653 // workaround for "empty" tree (only root) 00654 if (!this->root->hasChildren()){ 00655 min_value[0] = min_value[1] = min_value[2] = 0.0; 00656 max_value[0] = max_value[1] = max_value[2] = 0.0; 00657 size_changed = false; 00658 return; 00659 } 00660 00661 for (unsigned i = 0; i< 3; i++){ 00662 max_value[i] = -std::numeric_limits<double>::max(); 00663 min_value[i] = std::numeric_limits<double>::max(); 00664 } 00665 00666 for(typename OcTreeBaseImpl<NODE,I>::leaf_iterator it = this->begin(), 00667 end=this->end(); it!= end; ++it) 00668 { 00669 double size = it.getSize(); 00670 double halfSize = size/2.0; 00671 double x = it.getX() - halfSize; 00672 double y = it.getY() - halfSize; 00673 double z = it.getZ() - halfSize; 00674 if (x < min_value[0]) min_value[0] = x; 00675 if (y < min_value[1]) min_value[1] = y; 00676 if (z < min_value[2]) min_value[2] = z; 00677 00678 x += size; 00679 y += size; 00680 z += size; 00681 if (x > max_value[0]) max_value[0] = x; 00682 if (y > max_value[1]) max_value[1] = y; 00683 if (z > max_value[2]) max_value[2] = z; 00684 00685 } 00686 00687 size_changed = false; 00688 } 00689 00690 template <class NODE,class I> 00691 void OcTreeBaseImpl<NODE,I>::getMetricMin(double& x, double& y, double& z){ 00692 calcMinMax(); 00693 x = min_value[0]; 00694 y = min_value[1]; 00695 z = min_value[2]; 00696 } 00697 00698 template <class NODE,class I> 00699 void OcTreeBaseImpl<NODE,I>::getMetricMax(double& x, double& y, double& z){ 00700 calcMinMax(); 00701 x = max_value[0]; 00702 y = max_value[1]; 00703 z = max_value[2]; 00704 } 00705 00706 // const versions 00707 00708 template <class NODE,class I> 00709 void OcTreeBaseImpl<NODE,I>::getMetricMin(double& mx, double& my, double& mz) const { 00710 mx = my = mz = std::numeric_limits<double>::max( ); 00711 if (size_changed) { 00712 // workaround for "empty" tree (only root) 00713 if (!this->root->hasChildren()){ 00714 mx = my = mz = 0.0; 00715 return; 00716 } 00717 00718 for(typename OcTreeBaseImpl<NODE,I>::leaf_iterator it = this->begin(), 00719 end=this->end(); it!= end; ++it) { 00720 double halfSize = it.getSize()/2.0; 00721 double x = it.getX() - halfSize; 00722 double y = it.getY() - halfSize; 00723 double z = it.getZ() - halfSize; 00724 if (x < mx) mx = x; 00725 if (y < my) my = y; 00726 if (z < mz) mz = z; 00727 } 00728 } // end if size changed 00729 else { 00730 mx = min_value[0]; 00731 my = min_value[1]; 00732 mz = min_value[2]; 00733 } 00734 } 00735 00736 template <class NODE,class I> 00737 void OcTreeBaseImpl<NODE,I>::getMetricMax(double& mx, double& my, double& mz) const { 00738 mx = my = mz = -std::numeric_limits<double>::max( ); 00739 if (size_changed) { 00740 // workaround for "empty" tree (only root) 00741 if (!this->root->hasChildren()){ 00742 mx = my = mz = 0.0; 00743 return; 00744 } 00745 00746 for(typename OcTreeBaseImpl<NODE,I>::leaf_iterator it = this->begin(), 00747 end=this->end(); it!= end; ++it) { 00748 double halfSize = it.getSize()/2.0; 00749 double x = it.getX() + halfSize; 00750 double y = it.getY() + halfSize; 00751 double z = it.getZ() + halfSize; 00752 if (x > mx) mx = x; 00753 if (y > my) my = y; 00754 if (z > mz) mz = z; 00755 } 00756 } 00757 else { 00758 mx = max_value[0]; 00759 my = max_value[1]; 00760 mz = max_value[2]; 00761 } 00762 } 00763 00764 template <class NODE,class I> 00765 size_t OcTreeBaseImpl<NODE,I>::calcNumNodes() const { 00766 size_t retval = 1; // root node 00767 calcNumNodesRecurs(root, retval); 00768 return retval; 00769 } 00770 00771 template <class NODE,class I> 00772 void OcTreeBaseImpl<NODE,I>::calcNumNodesRecurs(NODE* node, size_t& num_nodes) const { 00773 assert (node != NULL); 00774 if (node->hasChildren()) { 00775 for (unsigned int i=0; i<8; ++i) { 00776 if (node->childExists(i)) { 00777 num_nodes++; 00778 calcNumNodesRecurs(node->getChild(i), num_nodes); 00779 } 00780 } 00781 } 00782 } 00783 00784 template <class NODE,class I> 00785 size_t OcTreeBaseImpl<NODE,I>::memoryUsage() const{ 00786 size_t num_leaf_nodes = this->getNumLeafNodes(); 00787 size_t num_inner_nodes = tree_size - num_leaf_nodes; 00788 return (sizeof(OcTreeBaseImpl<NODE,I>) + memoryUsageNode() * tree_size + num_inner_nodes * sizeof(NODE*[8])); 00789 } 00790 00791 template <class NODE,class I> 00792 void OcTreeBaseImpl<NODE,I>::getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax) const { 00793 00794 float diff[3]; 00795 unsigned int steps[3]; 00796 for (int i=0;i<3;++i) { 00797 diff[i] = pmax(i) - pmin(i); 00798 steps[i] = floor(diff[i] / this->resolution); 00799 // std::cout << "bbx " << i << " size: " << diff[i] << " " << steps[i] << " steps\n"; 00800 } 00801 00802 point3d p = pmin; 00803 NODE* res; 00804 for (unsigned int x=0; x<steps[0]; ++x) { 00805 p.x() += this->resolution; 00806 for (unsigned int y=0; y<steps[1]; ++y) { 00807 p.y() += this->resolution; 00808 for (unsigned int z=0; z<steps[2]; ++z) { 00809 // std::cout << "querying p=" << p << std::endl; 00810 p.z() += this->resolution; 00811 res = this->search(p); 00812 if (res == NULL) { 00813 node_centers.push_back(p); 00814 } 00815 } 00816 p.z() = pmin.z(); 00817 } 00818 p.y() = pmin.y(); 00819 } 00820 } 00821 00822 00823 template <class NODE,class I> 00824 size_t OcTreeBaseImpl<NODE,I>::getNumLeafNodes() const { 00825 return getNumLeafNodesRecurs(root); 00826 } 00827 00828 00829 template <class NODE,class I> 00830 size_t OcTreeBaseImpl<NODE,I>::getNumLeafNodesRecurs(const NODE* parent) const { 00831 00832 if (!parent->hasChildren()) return 1; // this is a leaf -> terminate 00833 00834 size_t sum_leafs_children = 0; 00835 for (unsigned int i=0; i<8; ++i) { 00836 if (parent->childExists(i)) { 00837 sum_leafs_children += getNumLeafNodesRecurs(parent->getChild(i)); 00838 } 00839 } 00840 return sum_leafs_children; 00841 } 00842 00843 00844 template <class NODE,class I> 00845 double OcTreeBaseImpl<NODE,I>::volume() { 00846 double x, y, z; 00847 getMetricSize(x, y, z); 00848 return x*y*z; 00849 } 00850 00851 00852 }