Skip to content

Commit

Permalink
Merge branch 'devel'
Browse files Browse the repository at this point in the history
  • Loading branch information
Armin Hornung committed May 26, 2014
2 parents 5c57599 + 118d757 commit 6d85527
Show file tree
Hide file tree
Showing 27 changed files with 187 additions and 100 deletions.
12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
OctoMap - A probabilistic, flexible, and compact 3D mapping library for robotic systems.
========================================================================================
OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees.
===========================================================================

http://octomap.github.io

Authors: Kai M. Wurm and Armin Hornung, University of Freiburg, Copyright (C) 2009-2014.
http://octomap.github.com

Originally developed by Kai M. Wurm and Armin Hornung, University of Freiburg, Copyright (C) 2009-2014.
Currently maintained by [Armin Hornung](https://github.com/ahornung).
See the [list of contributors](octomap/AUTHORS.txt) for further authors.

License:
Expand All @@ -13,7 +13,7 @@ License:


Download the latest releases:
https://github.com/octomap/octomap/tags
https://github.com/octomap/octomap/releases

API documentation:
http://octomap.github.com/octomap/doc/
Expand Down
5 changes: 3 additions & 2 deletions dynamicEDT3D/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@ ENABLE_TESTING()

# version (e.g. for packaging)
set(DYNAMICEDT3D_MAJOR_VERSION 1)
set(DYNAMICEDT3D_MINOR_VERSION 5)
set(DYNAMICEDT3D_PATCH_VERSION 0)
set(DYNAMICEDT3D_MINOR_VERSION 6)
set(DYNAMICEDT3D_PATCH_VERSION 6)
set(DYNAMICEDT3D_VERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION}.${DYNAMICEDT3D_PATCH_VERSION})
set(DYNAMICEDT3D_SOVERSION ${DYNAMICEDT3D_MAJOR_VERSION}.${DYNAMICEDT3D_MINOR_VERSION})

if(COMMAND cmake_policy)
cmake_policy(SET CMP0003 NEW)
Expand Down
25 changes: 25 additions & 0 deletions dynamicEDT3D/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<package>
<name>dynamic_edt_3d</name>
<version>1.6.6</version>
<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>

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

<url type="website">http://octomap.github.io</url>
<url type="bugtracker">https://github.com/OctoMap/octomap/issues</url>

<build_depend>octomap</build_depend>

<run_depend>octomap</run_depend>
<run_depend>catkin</run_depend>

<buildtool_depend>cmake</buildtool_depend>


<export>
<build_type>cmake</build_type>
</export>

</package>
4 changes: 4 additions & 0 deletions dynamicEDT3D/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@ SET( dynamicEDT3D_SRCS
)

add_library(dynamicedt3d SHARED ${dynamicEDT3D_SRCS})
set_target_properties(dynamicedt3d PROPERTIES
VERSION ${DYNAMICEDT3D_VERSION}
SOVERSION ${DYNAMICEDT3D_SOVERSION}
)
target_link_libraries(dynamicedt3d ${OCTOMAP_LIBRARIES})

add_library(dynamicedt3d-static STATIC ${dynamicEDT3D_SRCS})
Expand Down
10 changes: 6 additions & 4 deletions increase_version.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@



manifests=["octomap/package.xml","octovis/package.xml"]
cmakelists=["octomap/CMakeLists.txt","octovis/CMakeLists.txt"]
manifests=["octomap/package.xml","octovis/package.xml","dynamicEDT3D/package.xml"]
cmakelists=["octomap/CMakeLists.txt","octovis/CMakeLists.txt","dynamicEDT3D/CMakeLists.txt"]
versions = []

# find versions in package.xml
Expand Down Expand Up @@ -100,8 +100,10 @@
with open(manifest, 'w') as f:
f.write(new_package_str)

print "Finished writing package.xml and CMakeLists.txt files."
print "Now check the output, adjust CHANGELOG, \"git commit\", and run \"git tag v%s\"." % new_version_str
print "Finished writing package.xml and CMakeLists.txt files.\n"
print "Now check the output, adjust CHANGELOG, and \"git commit\".\nFinally, run:"
print " git checkout master && git merge --no-ff devel && git tag v%s" % new_version_str
print " git push && git push --tags"



Expand Down
9 changes: 9 additions & 0 deletions octomap/CHANGELOG.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,12 @@
v1.6.6: 2014-05-26
==================
- Support for SOVERSION in the libraries for better packaging
- Warning for unknown space in castRay() removed (needs to be inferred by
calling code depending on return value and endpoint voxel)
- Marching cubes for ray surface intersection extended
- Fixed QGLViewer include paths
- ScanGraph read error no longer exits the process

v1.6.5: 2014-03-14
==================
- Fix octovis includes for QGLViewer > 2.5
Expand Down
3 changes: 2 additions & 1 deletion octomap/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@ ENABLE_TESTING()
# version (e.g. for packaging)
set(OCTOMAP_MAJOR_VERSION 1)
set(OCTOMAP_MINOR_VERSION 6)
set(OCTOMAP_PATCH_VERSION 5)
set(OCTOMAP_PATCH_VERSION 6)
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)
cmake_policy(SET CMP0003 NEW)
endif(COMMAND cmake_policy)
Expand Down
28 changes: 16 additions & 12 deletions octomap/include/octomap/MCTables.h
Original file line number Diff line number Diff line change
Expand Up @@ -334,18 +334,22 @@ namespace octomap {
{-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}};

static const point3d vertexList[12] =
{point3d(0, 1, -1),
point3d(1, 0, -1),
point3d(0, -1, -1),
point3d(-1, 0, -1),
point3d(0, 1, 1),
point3d(1, 0, 1),
point3d(0, -1, 1),
point3d(-1, 0, 1),
point3d(-1, 1, 0),
point3d(1, 1, 0),
point3d(1, -1, 0),
point3d(-1, -1, 0)};
{
point3d(1, 0, -1),
point3d(0, -1, -1),
point3d(-1, 0, -1),
point3d(0, 1, -1),

point3d(1, 0, 1),
point3d(0, -1, 1),
point3d(-1, 0, 1),
point3d(0, 1, 1),

point3d(1, 1, 0),
point3d(1, -1, 0),
point3d(-1, -1, 0),
point3d(-1, 1, 0),
};

}
#endif
17 changes: 10 additions & 7 deletions octomap/include/octomap/OccupancyOcTreeBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -309,16 +309,19 @@ namespace octomap {
* Performs raycasting in 3d, similar to computeRay(). Can be called in parallel e.g. with OpenMP
* for a speedup.
*
* A ray is cast from origin with a given direction, the first occupied
* cell is returned (as center coordinate). If the starting coordinate is already
* occupied in the tree, this coordinate will be returned as a hit.
* A ray is cast from 'origin' with a given direction, the first non-free
* cell is returned in 'end' (as center coordinate). This could also be the
* origin node if it is occupied or unknown. castRay() returns true if an occupied node
* was hit by the raycast. If the raycast returns false you can search() the node at 'end' and
* see whether it's unknown space.
*
*
* @param[in] origin starting coordinate of ray
* @param[in] direction A vector pointing in the direction of the raycast. Does not need to be normalized.
* @param[out] end returns the center of the cell that was hit by the ray, if successful
* @param[in] ignoreUnknownCells whether unknown cells are ignored. If false (default), the raycast aborts when an unknown cell is hit.
* @param[in] direction A vector pointing in the direction of the raycast (NOT a point in space). Does not need to be normalized.
* @param[out] end returns the center of the last cell on the ray. If the function returns true, it is occupied.
* @param[in] ignoreUnknownCells whether unknown cells are ignored (= treated as free). If false (default), the raycast aborts when an unknown cell is hit and returns false.
* @param[in] maxRange Maximum range after which the raycast is aborted (<= 0: no limit, default)
* @return whether or not an occupied cell was hit
* @return true if an occupied cell was hit, false if the maximum range or octree bounds are reached, or if an unknown node was hit.
*/
virtual bool castRay(const point3d& origin, const point3d& direction, point3d& end,
bool ignoreUnknownCells=false, double maxRange=-1.0) const;
Expand Down
117 changes: 65 additions & 52 deletions octomap/include/octomap/OccupancyOcTreeBase.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -567,63 +567,78 @@ namespace octomap {
return false;
}

// OCTOMAP_WARNING("Normal for %f, %f, %f\n", point.x(), point.y(), point.z());

int vertex_values[8];

OcTreeKey current_key;
NODE* current_node;

int x_index[4] = {-1, 1, 1, -1};
int y_index[4] = {1, 1, -1, -1};
int z_index[2] = {-1, 1};

int k = 0;
for(int j = 0; j < 2; ++j){
for(int i = 0; i < 4; ++i){
current_key[0] = init_key[0] + x_index[i];
current_key[1] = init_key[1] + y_index[i];
current_key[2] = init_key[2] + z_index[j];
current_node = this->search(current_key);

if(current_node){
vertex_values[k] = this->isNodeOccupied(current_node);

// point3d coord = this->keyToCoord(current_key);
// OCTOMAP_WARNING_STR("vertex " << k << " at " << coord << "; value " << vertex_values[k]);
}else{
// Occupancy of unknown cells
vertex_values[k] = unknownStatus;
// There is 8 neighbouring sets
// The current cube can be at any of the 8 vertex
int x_index[4][4] = {{1, 1, 0, 0}, {1, 1, 0, 0}, {0, 0 -1, -1}, {0, 0 -1, -1}};
int y_index[4][4] = {{1, 0, 0, 1}, {0, -1, -1, 0}, {0, -1, -1, 0}, {1, 0, 0, 1}};
int z_index[2][2] = {{0, 1}, {-1, 0}};

// Iterate over the 8 neighboring sets
for(int m = 0; m < 2; ++m){
for(int l = 0; l < 4; ++l){

int k = 0;
// Iterate over the cubes
for(int j = 0; j < 2; ++j){
for(int i = 0; i < 4; ++i){
current_key[0] = init_key[0] + x_index[l][i];
current_key[1] = init_key[1] + y_index[l][i];
current_key[2] = init_key[2] + z_index[m][j];
current_node = this->search(current_key);

if(current_node){
vertex_values[k] = this->isNodeOccupied(current_node);

// point3d coord = this->keyToCoord(current_key);
// OCTOMAP_WARNING_STR("vertex " << k << " at " << coord << "; value " << vertex_values[k]);
}else{
// Occupancy of unknown cells
vertex_values[k] = unknownStatus;
}
++k;
}
}
++k;
}
}

int cube_index = 0;
if (vertex_values[0]) cube_index |= 1;
if (vertex_values[1]) cube_index |= 2;
if (vertex_values[2]) cube_index |= 4;
if (vertex_values[3]) cube_index |= 8;
if (vertex_values[4]) cube_index |= 16;
if (vertex_values[5]) cube_index |= 32;
if (vertex_values[6]) cube_index |= 64;
if (vertex_values[7]) cube_index |= 128;

// OCTOMAP_WARNING_STR("cubde_index: " << cube_index);

// All vertices are occupied or free resulting in no normal
if (edgeTable[cube_index] == 0)
return true;

// No interpolation is done yet, we use vertexList in <MCTables.h>.
for(int i = 0; triTable[cube_index][i] != -1; i += 3){
point3d p1 = vertexList[triTable[cube_index][i ]];
point3d p2 = vertexList[triTable[cube_index][i+1]];
point3d p3 = vertexList[triTable[cube_index][i+2]];
point3d v1 = p2 - p1;
point3d v2 = p3 - p1;

// Right hand side cross product to retrieve the normal in the good
// direction (pointing to the free nodes).
normals.push_back(v1.cross(v2).normalize());
int cube_index = 0;
if (vertex_values[0]) cube_index |= 1;
if (vertex_values[1]) cube_index |= 2;
if (vertex_values[2]) cube_index |= 4;
if (vertex_values[3]) cube_index |= 8;
if (vertex_values[4]) cube_index |= 16;
if (vertex_values[5]) cube_index |= 32;
if (vertex_values[6]) cube_index |= 64;
if (vertex_values[7]) cube_index |= 128;

// OCTOMAP_WARNING_STR("cubde_index: " << cube_index);

// All vertices are occupied or free resulting in no normal
if (edgeTable[cube_index] == 0)
return true;

// No interpolation is done yet, we use vertexList in <MCTables.h>.
for(int i = 0; triTable[cube_index][i] != -1; i += 3){
point3d p1 = vertexList[triTable[cube_index][i ]];
point3d p2 = vertexList[triTable[cube_index][i+1]];
point3d p3 = vertexList[triTable[cube_index][i+2]];
point3d v1 = p2 - p1;
point3d v2 = p3 - p1;

// OCTOMAP_WARNING("Vertex p1 %f, %f, %f\n", p1.x(), p1.y(), p1.z());
// OCTOMAP_WARNING("Vertex p2 %f, %f, %f\n", p2.x(), p2.y(), p2.z());
// OCTOMAP_WARNING("Vertex p3 %f, %f, %f\n", p3.x(), p3.y(), p3.z());

// Right hand side cross product to retrieve the normal in the good
// direction (pointing to the free nodes).
normals.push_back(v1.cross(v2).normalize());
}
}
}

return true;
Expand Down Expand Up @@ -651,7 +666,6 @@ namespace octomap {
return true;
}
} else if(!ignoreUnknown){
OCTOMAP_ERROR_STR("Origin node at " << origin << " for raycasting not found, does the node exist?");
end = this->keyToCoord(current_key);
return false;
}
Expand Down Expand Up @@ -746,7 +760,6 @@ namespace octomap {
}
// otherwise: node is free and valid, raycasting continues
} else if (!ignoreUnknown){ // no node found, this usually means we are in "unknown" areas
OCTOMAP_WARNING_STR("Search failed in OcTree::castRay() => an unknown area was hit in the map: " << end);
return false;
}
} // end while
Expand Down
4 changes: 3 additions & 1 deletion octomap/octomap-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,15 @@
# In your CMakeLists.txt, add these lines:
#
# FIND_PACKAGE(octomap REQUIRED )
# INCLUDE_DIRECTORIES(${OCTOMAP_INCLUDE_DIRS})
# TARGET_LINK_LIBRARIES(MY_TARGET_NAME ${OCTOMAP_LIBRARIES})
#
#
# This file will define the following variables:
# - OCTOMAP_LIBRARIES : The list of libraries to links against.
# - OCTOMAP_LIBRARY_DIRS : The directory where lib files are. Calling
# LINK_DIRECTORIES with this path is NOT needed.
# - OCTOMAP_INCLUDE_DIRS : The OpenCV include directories.
# - OCTOMAP_INCLUDE_DIRS : The OctoMap include directories.
#
# Based on the example CMake Tutorial
# http://www.vtk.org/Wiki/CMake/Tutorials/How_to_create_a_ProjectConfig.cmake_file
Expand Down
2 changes: 1 addition & 1 deletion octomap/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>octomap</name>
<version>1.6.5</version>
<version>1.6.6</version>
<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
http://octomap.github.io for details.</description>

Expand Down
4 changes: 4 additions & 0 deletions octomap/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@ SET (octomap_SRCS

# dynamic and static libs, see CMake FAQ:
ADD_LIBRARY( octomap SHARED ${octomap_SRCS})
set_target_properties( octomap PROPERTIES
VERSION ${OCTOMAP_VERSION}
SOVERSION ${OCTOMAP_SOVERSION}
)
ADD_LIBRARY( octomap-static STATIC ${octomap_SRCS})
SET_TARGET_PROPERTIES(octomap-static PROPERTIES OUTPUT_NAME "octomap")

Expand Down
4 changes: 2 additions & 2 deletions octomap/src/ScanGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,8 +363,8 @@ namespace octomap {

std::istream& ScanGraph::readBinary(std::ifstream &s) {
if (!s.is_open()){
OCTOMAP_ERROR_STR("Could not read from input filestream in ScanGraph::readBinary, exiting!");
exit(0);
OCTOMAP_ERROR_STR("Could not read from input filestream in ScanGraph::readBinary");
return s;
} else if (!s.good()){
OCTOMAP_WARNING_STR("Input filestream not \"good\" in ScanGraph::readBinary");
}
Expand Down
1 change: 1 addition & 0 deletions octomap/src/bt2vrml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,4 +98,5 @@ int main(int argc, char** argv) {

std::cout << "Finished writing "<< count << " voxels to " << vrmlFilename << std::endl;

return 0;
}
2 changes: 2 additions & 0 deletions octomap/src/compare_octrees.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,4 +153,6 @@ int main(int argc, char** argv) {

delete tree1;
delete tree2;

return 0;
}
4 changes: 2 additions & 2 deletions octomap/src/convert_octree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,6 @@ int main(int argc, char** argv) {


std::cout << "Finished writing to " << outputFilename << std::endl;
exit(0);


return 0;
}
Loading

0 comments on commit 6d85527

Please sign in to comment.