diff --git a/dynamicEDT3D/CMakeLists.txt b/dynamicEDT3D/CMakeLists.txt index 2debe960..cfc312ed 100644 --- a/dynamicEDT3D/CMakeLists.txt +++ b/dynamicEDT3D/CMakeLists.txt @@ -5,8 +5,8 @@ ENABLE_TESTING() # version (e.g. for packaging) set(DYNAMICEDT3D_MAJOR_VERSION 1) -set(DYNAMICEDT3D_MINOR_VERSION 6) -set(DYNAMICEDT3D_PATCH_VERSION 8) +set(DYNAMICEDT3D_MINOR_VERSION 7) +set(DYNAMICEDT3D_PATCH_VERSION 0) set(DYNAMICEDT3D_VERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}.${DYNAMICEDT3D_PATCH_VERSION}) set(DYNAMICEDT3D_SOVERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}) diff --git a/dynamicEDT3D/package.xml b/dynamicEDT3D/package.xml index de5c0fdc..b79de94f 100644 --- a/dynamicEDT3D/package.xml +++ b/dynamicEDT3D/package.xml @@ -1,6 +1,6 @@ dynamic_edt_3d - 1.6.8 + 1.7.0 The dynamicEDT3D library implements an inrementally updatable Euclidean distance transform (EDT) in 3D. It comes with a wrapper to use the OctoMap 3D representation and hooks into the change detection of the OctoMap library to propagate changes to the EDT. Christoph Sprunk diff --git a/octomap/CHANGELOG.txt b/octomap/CHANGELOG.txt index 6ae9c5e2..b5bfe550 100644 --- a/octomap/CHANGELOG.txt +++ b/octomap/CHANGELOG.txt @@ -1,3 +1,13 @@ +v1.7.0: 2015-11-27 +================== +- BBX iterators fixed for empty trees (thx to F. Boniardi) +- graph2tree tool option for nodes in global frame +- New octree2pointcloud PCL conversion tool (thx to F. Ferri) +- Improved change detection / diff calculation (thx to C. Brew) +- getUnknownLeafCenters now allows queries at a specified depth (thx to + A. Ecins) +- Fixed hashing overflow with clang (thx to L. Riano) + v1.6.7: 2014-08-31 ================== - FSF address in octovis license header for OctoMap package in Fedora diff --git a/octomap/CMakeLists.txt b/octomap/CMakeLists.txt index 2547ca09..026bf5a5 100644 --- a/octomap/CMakeLists.txt +++ b/octomap/CMakeLists.txt @@ -5,8 +5,8 @@ ENABLE_TESTING() # version (e.g. for packaging) set(OCTOMAP_MAJOR_VERSION 1) -set(OCTOMAP_MINOR_VERSION 6) -set(OCTOMAP_PATCH_VERSION 8) +set(OCTOMAP_MINOR_VERSION 7) +set(OCTOMAP_PATCH_VERSION 0) set(OCTOMAP_VERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION}.${OCTOMAP_PATCH_VERSION}) set(OCTOMAP_SOVERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION}) if(COMMAND cmake_policy) diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h index 3723c0eb..d825e12e 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.h +++ b/octomap/include/octomap/OcTreeBaseImpl.h @@ -213,7 +213,7 @@ namespace octomap { // -- access tree nodes ------------------ /// return centers of leafs that do NOT exist (but could) in a given bounding box - void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax) const; + void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth = 0) const; // -- raytracing ----------------------- @@ -259,9 +259,6 @@ namespace octomap { /// Pruning the tree first produces smaller files (lossless compression) std::ostream& writeData(std::ostream &s) const; - class leaf_iterator; - class tree_iterator; - class leaf_bbx_iterator; typedef leaf_iterator iterator; /// @return beginning of the tree as leaf iterator diff --git a/octomap/include/octomap/OcTreeBaseImpl.hxx b/octomap/include/octomap/OcTreeBaseImpl.hxx index 8d135429..85240430 100644 --- a/octomap/include/octomap/OcTreeBaseImpl.hxx +++ b/octomap/include/octomap/OcTreeBaseImpl.hxx @@ -327,10 +327,10 @@ namespace octomap { NODE* curNode (root); - unsigned int diff = tree_depth - depth; + int diff = tree_depth - depth; // follow nodes down to requested level (for diff = 0 it's the last level) - for (unsigned i=(tree_depth-1); i>=diff; --i) { + for (int i=(tree_depth-1); i>=diff; --i) { unsigned int pos = computeChildIdx(key_at_depth, i); if (curNode->childExists(pos)) { // cast needed: (nodes need to ensure it's the right pointer) @@ -856,26 +856,31 @@ namespace octomap { } template - void OcTreeBaseImpl::getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax) const { + void OcTreeBaseImpl::getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth) const { + assert(depth <= tree_depth); + if (depth == 0) + depth = tree_depth; + float diff[3]; unsigned int steps[3]; + float step_size = this->resolution * pow(2, tree_depth-depth); for (int i=0;i<3;++i) { diff[i] = pmax(i) - pmin(i); - steps[i] = floor(diff[i] / this->resolution); + steps[i] = floor(diff[i] / step_size); // std::cout << "bbx " << i << " size: " << diff[i] << " " << steps[i] << " steps\n"; } point3d p = pmin; NODE* res; for (unsigned int x=0; xresolution; + p.x() += step_size; for (unsigned int y=0; yresolution; + p.y() += step_size; for (unsigned int z=0; z (optional) \n" " -n (optional) \n" " -log (enable a detailed log file with statistics) \n" + " -g (nodes are already in global coordinates and no transformation is required) \n" " -compressML (enable maximum-likelihood compression (lossy) after every scan)\n" " -simple (simple scan insertion ray by ray instead of optimized) \n" " -discretize (approximate raycasting on discretized coordinates, speeds up insertion) \n" @@ -112,6 +113,7 @@ int main(int argc, char** argv) { bool detailedLog = false; bool simpleUpdate = false; bool discretize = false; + bool dontTransformNodes = false; unsigned char compression = 1; // get default sensor model values: @@ -137,6 +139,8 @@ int main(int argc, char** argv) { res = atof(argv[++arg]); else if (! strcmp(argv[arg], "-log")) detailedLog = true; + else if (! strcmp(argv[arg], "-g")) + dontTransformNodes = true; else if (! strcmp(argv[arg], "-simple")) simpleUpdate = true; else if (! strcmp(argv[arg], "-discretize")) @@ -205,15 +209,17 @@ int main(int argc, char** argv) { } // transform pointclouds first, so we can directly operate on them later - for (ScanGraph::iterator scan_it = graph->begin(); scan_it != graph->end(); scan_it++) { + if (!dontTransformNodes) { + for (ScanGraph::iterator scan_it = graph->begin(); scan_it != graph->end(); scan_it++) { - pose6d frame_origin = (*scan_it)->pose; - point3d sensor_origin = frame_origin.inv().transform((*scan_it)->pose.trans()); + pose6d frame_origin = (*scan_it)->pose; + point3d sensor_origin = frame_origin.inv().transform((*scan_it)->pose.trans()); - (*scan_it)->scan->transform(frame_origin); - point3d transformed_sensor_origin = frame_origin.transform(sensor_origin); - (*scan_it)->pose = pose6d(transformed_sensor_origin, octomath::Quaternion()); + (*scan_it)->scan->transform(frame_origin); + point3d transformed_sensor_origin = frame_origin.transform(sensor_origin); + (*scan_it)->pose = pose6d(transformed_sensor_origin, octomath::Quaternion()); + } } diff --git a/octomap/src/math/Quaternion.cpp b/octomap/src/math/Quaternion.cpp index 0aa57fde..d3f07baf 100644 --- a/octomap/src/math/Quaternion.cpp +++ b/octomap/src/math/Quaternion.cpp @@ -37,6 +37,7 @@ #include #include +#include // used from Vector: norm2, unit, * diff --git a/octomap/src/octree2pointcloud.cpp b/octomap/src/octree2pointcloud.cpp new file mode 100644 index 00000000..e971609c --- /dev/null +++ b/octomap/src/octree2pointcloud.cpp @@ -0,0 +1,114 @@ +/* + * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees + * http://octomap.github.com/ + * + * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg + * All rights reserved. + * License: New BSD + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the University of Freiburg nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace octomap; + +void printUsage(char* self){ + cerr << "USAGE: " << self << " \n"; + cerr << "This tool creates a point cloud of the occupied cells\n"; + exit(0); +} + + +int main(int argc, char** argv) { + if (argc != 3) + printUsage(argv[0]); + + string inputFilename = argv[1]; + string outputFilename = argv[2]; + + OcTree* tree = new OcTree(0.1); + if (!tree->readBinary(inputFilename)){ + OCTOMAP_ERROR("Could not open file, exiting.\n"); + exit(1); + } + + unsigned int maxDepth = tree->getTreeDepth(); + cout << "tree depth is " << maxDepth << endl; + + // expand collapsed occupied nodes until all occupied leaves are at maximum depth + vector collapsed_occ_nodes; + do { + collapsed_occ_nodes.clear(); + for (OcTree::iterator it = tree->begin(); it != tree->end(); ++it) + { + if(tree->isNodeOccupied(*it) && it.getDepth() < maxDepth) + { + collapsed_occ_nodes.push_back(&(*it)); + } + } + for (vector::iterator it = collapsed_occ_nodes.begin(); it != collapsed_occ_nodes.end(); ++it) + { + (*it)->expandNode(); + } + cout << "expanded " << collapsed_occ_nodes.size() << " nodes" << endl; + } while(collapsed_occ_nodes.size() > 0); + + vector pcl; + for (OcTree::iterator it = tree->begin(); it != tree->end(); ++it) + { + if(tree->isNodeOccupied(*it)) + { + pcl.push_back(it.getCoordinate()); + } + } + + delete tree; + + ofstream f(outputFilename.c_str(), ofstream::out); + f << "# .PCD v0.7" << endl + << "VERSION 0.7" << endl + << "FIELDS x y z" << endl + << "SIZE 4 4 4" << endl + << "TYPE F F F" << endl + << "COUNT 1 1 1" << endl + << "WIDTH " << pcl.size() << endl + << "HEIGHT 1" << endl + << "VIEWPOINT 0 0 0 0 0 0 1" << endl + << "POINTS " << pcl.size() << endl + << "DATA ascii" << endl; + for (size_t i = 0; i < pcl.size(); i++) + f << pcl[i].x() << " " << pcl[i].y() << " " << pcl[i].z() << endl; + f.close(); + + return 0; +} diff --git a/octomap/src/testing/test_iterators.cpp b/octomap/src/testing/test_iterators.cpp index 22d7dd1b..76a3118a 100644 --- a/octomap/src/testing/test_iterators.cpp +++ b/octomap/src/testing/test_iterators.cpp @@ -123,6 +123,92 @@ double timediff(const timeval& start, const timeval& stop){ return (stop.tv_sec - start.tv_sec) + 1.0e-6 *(stop.tv_usec - start.tv_usec); } +void boundingBoxTest(OcTree* tree){ + //tree->expand(); + // test complete tree (should be equal to no bbx) + OcTreeKey bbxMinKey, bbxMaxKey; + double temp_x,temp_y,temp_z; + tree->getMetricMin(temp_x,temp_y,temp_z); + octomap::point3d bbxMin(temp_x,temp_y,temp_z); + + tree->getMetricMax(temp_x,temp_y,temp_z); + octomap::point3d bbxMax(temp_x,temp_y,temp_z); + + EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey)); + EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey)); + + OcTree::leaf_bbx_iterator it_bbx = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey); + EXPECT_TRUE(it_bbx == tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey)); + OcTree::leaf_bbx_iterator end_bbx = tree->end_leafs_bbx(); + EXPECT_TRUE(end_bbx == tree->end_leafs_bbx()); + + OcTree::leaf_iterator it = tree->begin_leafs(); + EXPECT_TRUE(it == tree->begin_leafs()); + OcTree::leaf_iterator end = tree->end_leafs(); + EXPECT_TRUE(end == tree->end_leafs()); + + + for( ; it!= end && it_bbx != end_bbx; ++it, ++it_bbx){ + EXPECT_TRUE(it == it_bbx); + } + EXPECT_TRUE(it == end && it_bbx == end_bbx); + + + // now test an actual bounding box: + tree->expand(); // (currently only works properly for expanded tree (no multires) + bbxMin = point3d(-1, -1, - 1); + bbxMax = point3d(3, 2, 1); + EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey)); + EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey)); + + typedef unordered_ns::unordered_map KeyVolumeMap; + + KeyVolumeMap bbxVoxels; + + size_t count = 0; + for(OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey), end=tree->end_leafs_bbx(); + it!= end; ++it) + { + count++; + OcTreeKey currentKey = it.getKey(); + // leaf is actually a leaf: + EXPECT_FALSE(it->hasChildren()); + + // leaf exists in tree: + OcTreeNode* node = tree->search(currentKey); + EXPECT_TRUE(node); + EXPECT_EQ(node, &(*it)); + // all leafs are actually in the bbx: + for (unsigned i = 0; i < 3; ++i){ +// if (!(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i])){ +// std::cout << "Key failed: " << i << " " << currentKey[i] << " "<< bbxMinKey[i] << " "<< bbxMaxKey[i] +// << "size: "<< it.getSize()<< std::endl; +// } + EXPECT_TRUE(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i]); + } + + bbxVoxels.insert(std::pair(currentKey, it.getSize())); + } + EXPECT_EQ(bbxVoxels.size(), count); + std::cout << "Bounding box traversed ("<< count << " leaf nodes)\n\n"; + + + // compare with manual BBX check on all leafs: + for(OcTree::leaf_iterator it = tree->begin(), end=tree->end(); it!= end; ++it) { + OcTreeKey key = it.getKey(); + if ( key[0] >= bbxMinKey[0] && key[0] <= bbxMaxKey[0] + && key[1] >= bbxMinKey[1] && key[1] <= bbxMaxKey[1] + && key[2] >= bbxMinKey[2] && key[2] <= bbxMaxKey[2]) + { + KeyVolumeMap::iterator bbxIt = bbxVoxels.find(key); + EXPECT_FALSE(bbxIt == bbxVoxels.end()); + EXPECT_TRUE(key == bbxIt->first); + EXPECT_EQ(it.getSize(), bbxIt->second); + } + + } +} + int main(int argc, char** argv) { @@ -166,7 +252,6 @@ int main(int argc, char** argv) { } EXPECT_EQ(iteratedNodes, 0); - for(OcTree::leaf_iterator l_it = emptyTree.begin_leafs(maxDepth), l_end=emptyTree.end_leafs(); l_it!= l_end; ++l_it){ iteratedNodes++; } @@ -313,90 +398,11 @@ int main(int argc, char** argv) { /** * bounding box tests */ - //tree->expand(); - // test complete tree (should be equal to no bbx) - OcTreeKey bbxMinKey, bbxMaxKey; - double temp_x,temp_y,temp_z; - tree->getMetricMin(temp_x,temp_y,temp_z); - octomap::point3d bbxMin(temp_x,temp_y,temp_z); - - tree->getMetricMax(temp_x,temp_y,temp_z); - octomap::point3d bbxMax(temp_x,temp_y,temp_z); - - EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey)); - EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey)); - - OcTree::leaf_bbx_iterator it_bbx = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey); - EXPECT_TRUE(it_bbx == tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey)); - OcTree::leaf_bbx_iterator end_bbx = tree->end_leafs_bbx(); - EXPECT_TRUE(end_bbx == tree->end_leafs_bbx()); - - OcTree::leaf_iterator it = tree->begin_leafs(); - EXPECT_TRUE(it == tree->begin_leafs()); - OcTree::leaf_iterator end = tree->end_leafs(); - EXPECT_TRUE(end == tree->end_leafs()); - - - for( ; it!= end && it_bbx != end_bbx; ++it, ++it_bbx){ - EXPECT_TRUE(it == it_bbx); - } - EXPECT_TRUE(it == end && it_bbx == end_bbx); - - - // now test an actual bounding box: - tree->expand(); // (currently only works properly for expanded tree (no multires) - bbxMin = point3d(-1, -1, - 1); - bbxMax = point3d(3, 2, 1); - EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey)); - EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey)); - - typedef unordered_ns::unordered_map KeyVolumeMap; - - KeyVolumeMap bbxVoxels; + boundingBoxTest(tree); + boundingBoxTest(&emptyTree); - count = 0; - for(OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey), end=tree->end_leafs_bbx(); - it!= end; ++it) - { - count++; - OcTreeKey currentKey = it.getKey(); - // leaf is actually a leaf: - EXPECT_FALSE(it->hasChildren()); - - // leaf exists in tree: - OcTreeNode* node = tree->search(currentKey); - EXPECT_TRUE(node); - EXPECT_EQ(node, &(*it)); - // all leafs are actually in the bbx: - for (unsigned i = 0; i < 3; ++i){ -// if (!(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i])){ -// std::cout << "Key failed: " << i << " " << currentKey[i] << " "<< bbxMinKey[i] << " "<< bbxMaxKey[i] -// << "size: "<< it.getSize()<< std::endl; -// } - EXPECT_TRUE(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i]); - } - - bbxVoxels.insert(std::pair(currentKey, it.getSize())); - } - EXPECT_EQ(bbxVoxels.size(), count); - std::cout << "Bounding box traversed ("<< count << " leaf nodes)\n\n"; - - - // compare with manual BBX check on all leafs: - for(OcTree::leaf_iterator it = tree->begin(), end=tree->end(); it!= end; ++it) { - OcTreeKey key = it.getKey(); - if ( key[0] >= bbxMinKey[0] && key[0] <= bbxMaxKey[0] - && key[1] >= bbxMinKey[1] && key[1] <= bbxMaxKey[1] - && key[2] >= bbxMinKey[2] && key[2] <= bbxMaxKey[2]) - { - KeyVolumeMap::iterator bbxIt = bbxVoxels.find(key); - EXPECT_FALSE(bbxIt == bbxVoxels.end()); - EXPECT_TRUE(key == bbxIt->first); - EXPECT_EQ(it.getSize(), bbxIt->second); - } - - } + // test tree with one node: OcTree simpleTree(0.01); simpleTree.updateNode(point3d(10, 10, 10), 5.0f); diff --git a/octovis/CMakeLists.txt b/octovis/CMakeLists.txt index d1c89e4c..db70854c 100644 --- a/octovis/CMakeLists.txt +++ b/octovis/CMakeLists.txt @@ -3,8 +3,8 @@ PROJECT( octovis ) # # version (e.g. for packaging) set(OCTOVIS_MAJOR_VERSION 1) -set(OCTOVIS_MINOR_VERSION 6) -set(OCTOVIS_PATCH_VERSION 8) +set(OCTOVIS_MINOR_VERSION 7) +set(OCTOVIS_PATCH_VERSION 0) set(OCTOVIS_VERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION}.${OCTOVIS_PATCH_VERSION}) set(OCTOVIS_SOVERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION}) # get rid of a useless warning: diff --git a/octovis/package.xml b/octovis/package.xml index 819a6d26..e9f579a7 100644 --- a/octovis/package.xml +++ b/octovis/package.xml @@ -1,6 +1,6 @@ octovis - 1.6.8 + 1.7.0 octovis is visualization tool for the OctoMap library based on Qt and libQGLViewer. See http://octomap.github.io for details.