Skip to content

Commit 57eaec9

Browse files
committed
Merge branch 'devel' for 1.7.0 release
2 parents 17c3faf + 5ba840e commit 57eaec9

18 files changed

+268
-116
lines changed

dynamicEDT3D/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
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

Lines changed: 1 addition & 1 deletion
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="[email protected]">Christoph Sprunk</author>

octomap/CHANGELOG.txt

Lines changed: 10 additions & 0 deletions
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

Lines changed: 2 additions & 2 deletions
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

Lines changed: 1 addition & 4 deletions
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

Lines changed: 13 additions & 8 deletions
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

Lines changed: 3 additions & 0 deletions
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

Lines changed: 4 additions & 2 deletions
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

Lines changed: 6 additions & 2 deletions
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

Lines changed: 3 additions & 2 deletions
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 ) {

0 commit comments

Comments
 (0)