Skip to content

Commit 57eaec9

Browse files
committedNov 27, 2015
Merge branch 'devel' for 1.7.0 release
2 parents 17c3faf + 5ba840e commit 57eaec9

18 files changed

+268
-116
lines changed
 

‎dynamicEDT3D/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,8 @@ ENABLE_TESTING()
55

66
# version (e.g. for packaging)
77
set(DYNAMICEDT3D_MAJOR_VERSION 1)
8-
set(DYNAMICEDT3D_MINOR_VERSION 6)
9-
set(DYNAMICEDT3D_PATCH_VERSION 8)
8+
set(DYNAMICEDT3D_MINOR_VERSION 7)
9+
set(DYNAMICEDT3D_PATCH_VERSION 0)
1010
set(DYNAMICEDT3D_VERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}.${DYNAMICEDT3D_PATCH_VERSION})
1111
set(DYNAMICEDT3D_SOVERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION})
1212

‎dynamicEDT3D/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package>
22
<name>dynamic_edt_3d</name>
3-
<version>1.6.8</version>
3+
<version>1.7.0</version>
44
<description> 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.</description>
55

66
<author email="sprunkc@informatik.uni-freiburg.de">Christoph Sprunk</author>

‎octomap/CHANGELOG.txt

+10
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,13 @@
1+
v1.7.0: 2015-11-27
2+
==================
3+
- BBX iterators fixed for empty trees (thx to F. Boniardi)
4+
- graph2tree tool option for nodes in global frame
5+
- New octree2pointcloud PCL conversion tool (thx to F. Ferri)
6+
- Improved change detection / diff calculation (thx to C. Brew)
7+
- getUnknownLeafCenters now allows queries at a specified depth (thx to
8+
A. Ecins)
9+
- Fixed hashing overflow with clang (thx to L. Riano)
10+
111
v1.6.7: 2014-08-31
212
==================
313
- FSF address in octovis license header for OctoMap package in Fedora

‎octomap/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,8 @@ ENABLE_TESTING()
55

66
# version (e.g. for packaging)
77
set(OCTOMAP_MAJOR_VERSION 1)
8-
set(OCTOMAP_MINOR_VERSION 6)
9-
set(OCTOMAP_PATCH_VERSION 8)
8+
set(OCTOMAP_MINOR_VERSION 7)
9+
set(OCTOMAP_PATCH_VERSION 0)
1010
set(OCTOMAP_VERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION}.${OCTOMAP_PATCH_VERSION})
1111
set(OCTOMAP_SOVERSION ${OCTOMAP_MAJOR_VERSION}.${OCTOMAP_MINOR_VERSION})
1212
if(COMMAND cmake_policy)

‎octomap/include/octomap/OcTreeBaseImpl.h

+1-4
Original file line numberDiff line numberDiff line change
@@ -213,7 +213,7 @@ namespace octomap {
213213
// -- access tree nodes ------------------
214214

215215
/// return centers of leafs that do NOT exist (but could) in a given bounding box
216-
void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax) const;
216+
void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth = 0) const;
217217

218218

219219
// -- raytracing -----------------------
@@ -259,9 +259,6 @@ namespace octomap {
259259
/// Pruning the tree first produces smaller files (lossless compression)
260260
std::ostream& writeData(std::ostream &s) const;
261261

262-
class leaf_iterator;
263-
class tree_iterator;
264-
class leaf_bbx_iterator;
265262
typedef leaf_iterator iterator;
266263

267264
/// @return beginning of the tree as leaf iterator

‎octomap/include/octomap/OcTreeBaseImpl.hxx

+13-8
Original file line numberDiff line numberDiff line change
@@ -327,10 +327,10 @@ namespace octomap {
327327

328328
NODE* curNode (root);
329329

330-
unsigned int diff = tree_depth - depth;
330+
int diff = tree_depth - depth;
331331

332332
// follow nodes down to requested level (for diff = 0 it's the last level)
333-
for (unsigned i=(tree_depth-1); i>=diff; --i) {
333+
for (int i=(tree_depth-1); i>=diff; --i) {
334334
unsigned int pos = computeChildIdx(key_at_depth, i);
335335
if (curNode->childExists(pos)) {
336336
// cast needed: (nodes need to ensure it's the right pointer)
@@ -856,26 +856,31 @@ namespace octomap {
856856
}
857857

858858
template <class NODE,class I>
859-
void OcTreeBaseImpl<NODE,I>::getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax) const {
859+
void OcTreeBaseImpl<NODE,I>::getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth) const {
860860

861+
assert(depth <= tree_depth);
862+
if (depth == 0)
863+
depth = tree_depth;
864+
861865
float diff[3];
862866
unsigned int steps[3];
867+
float step_size = this->resolution * pow(2, tree_depth-depth);
863868
for (int i=0;i<3;++i) {
864869
diff[i] = pmax(i) - pmin(i);
865-
steps[i] = floor(diff[i] / this->resolution);
870+
steps[i] = floor(diff[i] / step_size);
866871
// std::cout << "bbx " << i << " size: " << diff[i] << " " << steps[i] << " steps\n";
867872
}
868873

869874
point3d p = pmin;
870875
NODE* res;
871876
for (unsigned int x=0; x<steps[0]; ++x) {
872-
p.x() += this->resolution;
877+
p.x() += step_size;
873878
for (unsigned int y=0; y<steps[1]; ++y) {
874-
p.y() += this->resolution;
879+
p.y() += step_size;
875880
for (unsigned int z=0; z<steps[2]; ++z) {
876881
// std::cout << "querying p=" << p << std::endl;
877-
p.z() += this->resolution;
878-
res = this->search(p);
882+
p.z() += step_size;
883+
res = this->search(p,depth);
879884
if (res == NULL) {
880885
node_centers.push_back(p);
881886
}

‎octomap/include/octomap/OcTreeIterator.hxx

+3
Original file line numberDiff line numberDiff line change
@@ -375,9 +375,12 @@
375375
leaf_bbx_iterator(OcTreeBaseImpl<NodeType,INTERFACE> const* tree, const OcTreeKey& min, const OcTreeKey& max, unsigned char depth=0)
376376
: iterator_base(tree, depth), minKey(min), maxKey(max)
377377
{
378+
// tree could be empty (= no stack)
379+
if (this->stack.size() > 0){
378380
// advance from root to next valid leaf in bbx:
379381
this->stack.push(this->stack.top());
380382
this->operator ++();
383+
}
381384
}
382385

383386
leaf_bbx_iterator(const leaf_bbx_iterator& other) : iterator_base(other) {

‎octomap/include/octomap/OcTreeKey.h

+4-2
Original file line numberDiff line numberDiff line change
@@ -96,8 +96,10 @@ namespace octomap {
9696
/// Provides a hash function on Keys
9797
struct KeyHash{
9898
size_t operator()(const OcTreeKey& key) const{
99-
// a hashing function
100-
return key.k[0] + 1337*key.k[1] + 345637*key.k[2];
99+
// a simple hashing function
100+
// explicit casts to size_t to operate on the complete range
101+
// constanst will be promoted according to C++ standard
102+
return size_t(key.k[0]) + 1447*size_t(key.k[1]) + 345637*size_t(key.k[2]);
101103
}
102104
};
103105

‎octomap/include/octomap/OccupancyOcTreeBase.h

+6-2
Original file line numberDiff line numberDiff line change
@@ -375,6 +375,7 @@ namespace octomap {
375375
//-- change detection on occupancy:
376376
/// track or ignore changes while inserting scans (default: ignore)
377377
void enableChangeDetection(bool enable) { use_change_detection = enable; }
378+
bool isChangeDetectionEnabled() const { return use_change_detection; }
378379
/// Reset the set of changed keys. Call this after you obtained all changed nodes.
379380
void resetChangeDetection() { changed_keys.clear(); }
380381

@@ -383,10 +384,13 @@ namespace octomap {
383384
* you need to enableChangeDetection() first. Here, an OcTreeKey always
384385
* refers to a node at the lowest tree level (its size is the minimum tree resolution)
385386
*/
386-
KeyBoolMap::const_iterator changedKeysBegin() {return changed_keys.begin();}
387+
KeyBoolMap::const_iterator changedKeysBegin() const {return changed_keys.begin();}
387388

388389
/// Iterator to traverse all keys of changed nodes.
389-
KeyBoolMap::const_iterator changedKeysEnd() {return changed_keys.end();}
390+
KeyBoolMap::const_iterator changedKeysEnd() const {return changed_keys.end();}
391+
392+
/// Number of changes since last reset.
393+
size_t numChangesDetected() const { return changed_keys.size(); }
390394

391395

392396
/**

‎octomap/include/octomap/OccupancyOcTreeBase.hxx

+3-2
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
*/
3333

3434
#include <bitset>
35+
#include <algorithm>
3536

3637
#include <octomap/MCTables.h>
3738

@@ -365,13 +366,13 @@ namespace octomap {
365366
template <class NODE>
366367
NODE* OccupancyOcTreeBase<NODE>::updateNodeRecurs(NODE* node, bool node_just_created, const OcTreeKey& key,
367368
unsigned int depth, const float& log_odds_update, bool lazy_eval) {
368-
unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth);
369369
bool created_node = false;
370370

371371
assert(node);
372372

373373
// follow down to last level
374374
if (depth < this->tree_depth) {
375+
unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth);
375376
if (!node->childExists(pos)) {
376377
// child does not exist, but maybe it's a pruned node?
377378
if ((!node->hasChildren()) && !node_just_created ) {
@@ -434,13 +435,13 @@ namespace octomap {
434435
template <class NODE>
435436
NODE* OccupancyOcTreeBase<NODE>::setNodeValueRecurs(NODE* node, bool node_just_created, const OcTreeKey& key,
436437
unsigned int depth, const float& log_odds_value, bool lazy_eval) {
437-
unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth);
438438
bool created_node = false;
439439

440440
assert(node);
441441

442442
// follow down to last level
443443
if (depth < this->tree_depth) {
444+
unsigned int pos = computeChildIdx(key, this->tree_depth -1 - depth);
444445
if (!node->childExists(pos)) {
445446
// child does not exist, but maybe it's a pruned node?
446447
if ((!node->hasChildren()) && !node_just_created ) {

‎octomap/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package>
22
<name>octomap</name>
3-
<version>1.6.8</version>
3+
<version>1.7.0</version>
44
<description>The OctoMap library implements a 3D occupancy grid mapping approach, providing data structures and mapping algorithms in C++. The map implementation is based on an octree. See
55
http://octomap.github.io for details.</description>
66

‎octomap/src/CMakeLists.txt

+3
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,9 @@ TARGET_LINK_LIBRARIES(normals_example octomap)
5757
ADD_EXECUTABLE(intersection_example intersection_example.cpp)
5858
TARGET_LINK_LIBRARIES(intersection_example octomap)
5959

60+
ADD_EXECUTABLE(octree2pointcloud octree2pointcloud.cpp)
61+
TARGET_LINK_LIBRARIES(octree2pointcloud octomap)
62+
6063

6164
# installation:
6265
# store all header files to install:

‎octomap/src/graph2tree.cpp

+12-6
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ void printUsage(char* self){
5757
" -m <maxrange> (optional) \n"
5858
" -n <max scan no.> (optional) \n"
5959
" -log (enable a detailed log file with statistics) \n"
60+
" -g (nodes are already in global coordinates and no transformation is required) \n"
6061
" -compressML (enable maximum-likelihood compression (lossy) after every scan)\n"
6162
" -simple (simple scan insertion ray by ray instead of optimized) \n"
6263
" -discretize (approximate raycasting on discretized coordinates, speeds up insertion) \n"
@@ -112,6 +113,7 @@ int main(int argc, char** argv) {
112113
bool detailedLog = false;
113114
bool simpleUpdate = false;
114115
bool discretize = false;
116+
bool dontTransformNodes = false;
115117
unsigned char compression = 1;
116118

117119
// get default sensor model values:
@@ -137,6 +139,8 @@ int main(int argc, char** argv) {
137139
res = atof(argv[++arg]);
138140
else if (! strcmp(argv[arg], "-log"))
139141
detailedLog = true;
142+
else if (! strcmp(argv[arg], "-g"))
143+
dontTransformNodes = true;
140144
else if (! strcmp(argv[arg], "-simple"))
141145
simpleUpdate = true;
142146
else if (! strcmp(argv[arg], "-discretize"))
@@ -205,15 +209,17 @@ int main(int argc, char** argv) {
205209
}
206210

207211
// transform pointclouds first, so we can directly operate on them later
208-
for (ScanGraph::iterator scan_it = graph->begin(); scan_it != graph->end(); scan_it++) {
212+
if (!dontTransformNodes) {
213+
for (ScanGraph::iterator scan_it = graph->begin(); scan_it != graph->end(); scan_it++) {
209214

210-
pose6d frame_origin = (*scan_it)->pose;
211-
point3d sensor_origin = frame_origin.inv().transform((*scan_it)->pose.trans());
215+
pose6d frame_origin = (*scan_it)->pose;
216+
point3d sensor_origin = frame_origin.inv().transform((*scan_it)->pose.trans());
212217

213-
(*scan_it)->scan->transform(frame_origin);
214-
point3d transformed_sensor_origin = frame_origin.transform(sensor_origin);
215-
(*scan_it)->pose = pose6d(transformed_sensor_origin, octomath::Quaternion());
218+
(*scan_it)->scan->transform(frame_origin);
219+
point3d transformed_sensor_origin = frame_origin.transform(sensor_origin);
220+
(*scan_it)->pose = pose6d(transformed_sensor_origin, octomath::Quaternion());
216221

222+
}
217223
}
218224

219225

‎octomap/src/math/Quaternion.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737

3838
#include <cassert>
3939
#include <math.h>
40+
#include <algorithm>
4041

4142

4243
// used from Vector: norm2, unit, *

‎octomap/src/octree2pointcloud.cpp

+114
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,114 @@
1+
/*
2+
* OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
3+
* http://octomap.github.com/
4+
*
5+
* Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
6+
* All rights reserved.
7+
* License: New BSD
8+
*
9+
* Redistribution and use in source and binary forms, with or without
10+
* modification, are permitted provided that the following conditions are met:
11+
*
12+
* * Redistributions of source code must retain the above copyright
13+
* notice, this list of conditions and the following disclaimer.
14+
* * Redistributions in binary form must reproduce the above copyright
15+
* notice, this list of conditions and the following disclaimer in the
16+
* documentation and/or other materials provided with the distribution.
17+
* * Neither the name of the University of Freiburg nor the names of its
18+
* contributors may be used to endorse or promote products derived from
19+
* this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24+
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25+
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26+
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27+
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28+
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29+
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30+
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31+
* POSSIBILITY OF SUCH DAMAGE.
32+
*/
33+
34+
#include <string.h>
35+
#include <stdlib.h>
36+
#include <iostream>
37+
#include <fstream>
38+
39+
#include <octomap/octomap.h>
40+
#include <octomap/octomap_timing.h>
41+
42+
using namespace std;
43+
using namespace octomap;
44+
45+
void printUsage(char* self){
46+
cerr << "USAGE: " << self << " <InputFile.bt> <OutputFile.pcd>\n";
47+
cerr << "This tool creates a point cloud of the occupied cells\n";
48+
exit(0);
49+
}
50+
51+
52+
int main(int argc, char** argv) {
53+
if (argc != 3)
54+
printUsage(argv[0]);
55+
56+
string inputFilename = argv[1];
57+
string outputFilename = argv[2];
58+
59+
OcTree* tree = new OcTree(0.1);
60+
if (!tree->readBinary(inputFilename)){
61+
OCTOMAP_ERROR("Could not open file, exiting.\n");
62+
exit(1);
63+
}
64+
65+
unsigned int maxDepth = tree->getTreeDepth();
66+
cout << "tree depth is " << maxDepth << endl;
67+
68+
// expand collapsed occupied nodes until all occupied leaves are at maximum depth
69+
vector<OcTreeNode*> collapsed_occ_nodes;
70+
do {
71+
collapsed_occ_nodes.clear();
72+
for (OcTree::iterator it = tree->begin(); it != tree->end(); ++it)
73+
{
74+
if(tree->isNodeOccupied(*it) && it.getDepth() < maxDepth)
75+
{
76+
collapsed_occ_nodes.push_back(&(*it));
77+
}
78+
}
79+
for (vector<OcTreeNode*>::iterator it = collapsed_occ_nodes.begin(); it != collapsed_occ_nodes.end(); ++it)
80+
{
81+
(*it)->expandNode();
82+
}
83+
cout << "expanded " << collapsed_occ_nodes.size() << " nodes" << endl;
84+
} while(collapsed_occ_nodes.size() > 0);
85+
86+
vector<point3d> pcl;
87+
for (OcTree::iterator it = tree->begin(); it != tree->end(); ++it)
88+
{
89+
if(tree->isNodeOccupied(*it))
90+
{
91+
pcl.push_back(it.getCoordinate());
92+
}
93+
}
94+
95+
delete tree;
96+
97+
ofstream f(outputFilename.c_str(), ofstream::out);
98+
f << "# .PCD v0.7" << endl
99+
<< "VERSION 0.7" << endl
100+
<< "FIELDS x y z" << endl
101+
<< "SIZE 4 4 4" << endl
102+
<< "TYPE F F F" << endl
103+
<< "COUNT 1 1 1" << endl
104+
<< "WIDTH " << pcl.size() << endl
105+
<< "HEIGHT 1" << endl
106+
<< "VIEWPOINT 0 0 0 0 0 0 1" << endl
107+
<< "POINTS " << pcl.size() << endl
108+
<< "DATA ascii" << endl;
109+
for (size_t i = 0; i < pcl.size(); i++)
110+
f << pcl[i].x() << " " << pcl[i].y() << " " << pcl[i].z() << endl;
111+
f.close();
112+
113+
return 0;
114+
}

‎octomap/src/testing/test_iterators.cpp

+89-83
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,92 @@ double timediff(const timeval& start, const timeval& stop){
123123
return (stop.tv_sec - start.tv_sec) + 1.0e-6 *(stop.tv_usec - start.tv_usec);
124124
}
125125

126+
void boundingBoxTest(OcTree* tree){
127+
//tree->expand();
128+
// test complete tree (should be equal to no bbx)
129+
OcTreeKey bbxMinKey, bbxMaxKey;
130+
double temp_x,temp_y,temp_z;
131+
tree->getMetricMin(temp_x,temp_y,temp_z);
132+
octomap::point3d bbxMin(temp_x,temp_y,temp_z);
133+
134+
tree->getMetricMax(temp_x,temp_y,temp_z);
135+
octomap::point3d bbxMax(temp_x,temp_y,temp_z);
136+
137+
EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey));
138+
EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey));
139+
140+
OcTree::leaf_bbx_iterator it_bbx = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey);
141+
EXPECT_TRUE(it_bbx == tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey));
142+
OcTree::leaf_bbx_iterator end_bbx = tree->end_leafs_bbx();
143+
EXPECT_TRUE(end_bbx == tree->end_leafs_bbx());
144+
145+
OcTree::leaf_iterator it = tree->begin_leafs();
146+
EXPECT_TRUE(it == tree->begin_leafs());
147+
OcTree::leaf_iterator end = tree->end_leafs();
148+
EXPECT_TRUE(end == tree->end_leafs());
149+
150+
151+
for( ; it!= end && it_bbx != end_bbx; ++it, ++it_bbx){
152+
EXPECT_TRUE(it == it_bbx);
153+
}
154+
EXPECT_TRUE(it == end && it_bbx == end_bbx);
155+
156+
157+
// now test an actual bounding box:
158+
tree->expand(); // (currently only works properly for expanded tree (no multires)
159+
bbxMin = point3d(-1, -1, - 1);
160+
bbxMax = point3d(3, 2, 1);
161+
EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey));
162+
EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey));
163+
164+
typedef unordered_ns::unordered_map<OcTreeKey, double, OcTreeKey::KeyHash> KeyVolumeMap;
165+
166+
KeyVolumeMap bbxVoxels;
167+
168+
size_t count = 0;
169+
for(OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey), end=tree->end_leafs_bbx();
170+
it!= end; ++it)
171+
{
172+
count++;
173+
OcTreeKey currentKey = it.getKey();
174+
// leaf is actually a leaf:
175+
EXPECT_FALSE(it->hasChildren());
176+
177+
// leaf exists in tree:
178+
OcTreeNode* node = tree->search(currentKey);
179+
EXPECT_TRUE(node);
180+
EXPECT_EQ(node, &(*it));
181+
// all leafs are actually in the bbx:
182+
for (unsigned i = 0; i < 3; ++i){
183+
// if (!(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i])){
184+
// std::cout << "Key failed: " << i << " " << currentKey[i] << " "<< bbxMinKey[i] << " "<< bbxMaxKey[i]
185+
// << "size: "<< it.getSize()<< std::endl;
186+
// }
187+
EXPECT_TRUE(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i]);
188+
}
189+
190+
bbxVoxels.insert(std::pair<OcTreeKey,double>(currentKey, it.getSize()));
191+
}
192+
EXPECT_EQ(bbxVoxels.size(), count);
193+
std::cout << "Bounding box traversed ("<< count << " leaf nodes)\n\n";
194+
195+
196+
// compare with manual BBX check on all leafs:
197+
for(OcTree::leaf_iterator it = tree->begin(), end=tree->end(); it!= end; ++it) {
198+
OcTreeKey key = it.getKey();
199+
if ( key[0] >= bbxMinKey[0] && key[0] <= bbxMaxKey[0]
200+
&& key[1] >= bbxMinKey[1] && key[1] <= bbxMaxKey[1]
201+
&& key[2] >= bbxMinKey[2] && key[2] <= bbxMaxKey[2])
202+
{
203+
KeyVolumeMap::iterator bbxIt = bbxVoxels.find(key);
204+
EXPECT_FALSE(bbxIt == bbxVoxels.end());
205+
EXPECT_TRUE(key == bbxIt->first);
206+
EXPECT_EQ(it.getSize(), bbxIt->second);
207+
}
208+
209+
}
210+
}
211+
126212
int main(int argc, char** argv) {
127213

128214

@@ -166,7 +252,6 @@ int main(int argc, char** argv) {
166252
}
167253
EXPECT_EQ(iteratedNodes, 0);
168254

169-
170255
for(OcTree::leaf_iterator l_it = emptyTree.begin_leafs(maxDepth), l_end=emptyTree.end_leafs(); l_it!= l_end; ++l_it){
171256
iteratedNodes++;
172257
}
@@ -313,90 +398,11 @@ int main(int argc, char** argv) {
313398
/**
314399
* bounding box tests
315400
*/
316-
//tree->expand();
317-
// test complete tree (should be equal to no bbx)
318-
OcTreeKey bbxMinKey, bbxMaxKey;
319-
double temp_x,temp_y,temp_z;
320-
tree->getMetricMin(temp_x,temp_y,temp_z);
321-
octomap::point3d bbxMin(temp_x,temp_y,temp_z);
322-
323-
tree->getMetricMax(temp_x,temp_y,temp_z);
324-
octomap::point3d bbxMax(temp_x,temp_y,temp_z);
325-
326-
EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey));
327-
EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey));
328-
329-
OcTree::leaf_bbx_iterator it_bbx = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey);
330-
EXPECT_TRUE(it_bbx == tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey));
331-
OcTree::leaf_bbx_iterator end_bbx = tree->end_leafs_bbx();
332-
EXPECT_TRUE(end_bbx == tree->end_leafs_bbx());
333-
334-
OcTree::leaf_iterator it = tree->begin_leafs();
335-
EXPECT_TRUE(it == tree->begin_leafs());
336-
OcTree::leaf_iterator end = tree->end_leafs();
337-
EXPECT_TRUE(end == tree->end_leafs());
338-
339-
340-
for( ; it!= end && it_bbx != end_bbx; ++it, ++it_bbx){
341-
EXPECT_TRUE(it == it_bbx);
342-
}
343-
EXPECT_TRUE(it == end && it_bbx == end_bbx);
344-
345-
346-
// now test an actual bounding box:
347-
tree->expand(); // (currently only works properly for expanded tree (no multires)
348-
bbxMin = point3d(-1, -1, - 1);
349-
bbxMax = point3d(3, 2, 1);
350-
EXPECT_TRUE(tree->coordToKeyChecked(bbxMin, bbxMinKey));
351-
EXPECT_TRUE(tree->coordToKeyChecked(bbxMax, bbxMaxKey));
352-
353-
typedef unordered_ns::unordered_map<OcTreeKey, double, OcTreeKey::KeyHash> KeyVolumeMap;
354-
355-
KeyVolumeMap bbxVoxels;
401+
boundingBoxTest(tree);
402+
boundingBoxTest(&emptyTree);
356403

357-
count = 0;
358-
for(OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(bbxMinKey,bbxMaxKey), end=tree->end_leafs_bbx();
359-
it!= end; ++it)
360-
{
361-
count++;
362-
OcTreeKey currentKey = it.getKey();
363-
// leaf is actually a leaf:
364-
EXPECT_FALSE(it->hasChildren());
365-
366-
// leaf exists in tree:
367-
OcTreeNode* node = tree->search(currentKey);
368-
EXPECT_TRUE(node);
369-
EXPECT_EQ(node, &(*it));
370-
// all leafs are actually in the bbx:
371-
for (unsigned i = 0; i < 3; ++i){
372-
// if (!(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i])){
373-
// std::cout << "Key failed: " << i << " " << currentKey[i] << " "<< bbxMinKey[i] << " "<< bbxMaxKey[i]
374-
// << "size: "<< it.getSize()<< std::endl;
375-
// }
376-
EXPECT_TRUE(currentKey[i] >= bbxMinKey[i] && currentKey[i] <= bbxMaxKey[i]);
377-
}
378-
379-
bbxVoxels.insert(std::pair<OcTreeKey,double>(currentKey, it.getSize()));
380-
}
381-
EXPECT_EQ(bbxVoxels.size(), count);
382-
std::cout << "Bounding box traversed ("<< count << " leaf nodes)\n\n";
383-
384-
385-
// compare with manual BBX check on all leafs:
386-
for(OcTree::leaf_iterator it = tree->begin(), end=tree->end(); it!= end; ++it) {
387-
OcTreeKey key = it.getKey();
388-
if ( key[0] >= bbxMinKey[0] && key[0] <= bbxMaxKey[0]
389-
&& key[1] >= bbxMinKey[1] && key[1] <= bbxMaxKey[1]
390-
&& key[2] >= bbxMinKey[2] && key[2] <= bbxMaxKey[2])
391-
{
392-
KeyVolumeMap::iterator bbxIt = bbxVoxels.find(key);
393-
EXPECT_FALSE(bbxIt == bbxVoxels.end());
394-
EXPECT_TRUE(key == bbxIt->first);
395-
EXPECT_EQ(it.getSize(), bbxIt->second);
396-
}
397-
398-
}
399404

405+
400406
// test tree with one node:
401407
OcTree simpleTree(0.01);
402408
simpleTree.updateNode(point3d(10, 10, 10), 5.0f);

‎octovis/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,8 @@ PROJECT( octovis )
33

44
# # version (e.g. for packaging)
55
set(OCTOVIS_MAJOR_VERSION 1)
6-
set(OCTOVIS_MINOR_VERSION 6)
7-
set(OCTOVIS_PATCH_VERSION 8)
6+
set(OCTOVIS_MINOR_VERSION 7)
7+
set(OCTOVIS_PATCH_VERSION 0)
88
set(OCTOVIS_VERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION}.${OCTOVIS_PATCH_VERSION})
99
set(OCTOVIS_SOVERSION ${OCTOVIS_MAJOR_VERSION}.${OCTOVIS_MINOR_VERSION})
1010
# get rid of a useless warning:

‎octovis/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package>
22
<name>octovis</name>
3-
<version>1.6.8</version>
3+
<version>1.7.0</version>
44
<description>octovis is visualization tool for the OctoMap library based on Qt and libQGLViewer. See
55
http://octomap.github.io for details.</description>
66

0 commit comments

Comments
 (0)
Please sign in to comment.