Unverified Commit 2fb20e16 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by GitHub
Browse files

Merge pull request #30 from jcarpent/devel

Fix bug when OCTOMAP is not found
parents af40b024 5347ca4d
......@@ -78,19 +78,19 @@ add_optional_dependency("octomap >= 1.6")
if (OCTOMAP_INCLUDE_DIRS AND OCTOMAP_LIBRARY_DIRS)
include_directories(${OCTOMAP_INCLUDE_DIRS})
link_directories(${OCTOMAP_LIBRARY_DIRS})
set(FCL_HAVE_OCTOMAP 1)
string(REPLACE "." ";" VERSION_LIST ${OCTOMAP_VERSION})
list(GET VERSION_LIST 0 OCTOMAP_MAJOR_VERSION)
list(GET VERSION_LIST 1 OCTOMAP_MINOR_VERSION)
list(GET VERSION_LIST 2 OCTOMAP_PATCH_VERSION)
add_definitions (-DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION}
-DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION}
-DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION})
add_definitions (-DFCL_HAVE_OCTOMAP)
string(REPLACE "." ";" VERSION_LIST ${OCTOMAP_VERSION})
list(GET VERSION_LIST 0 OCTOMAP_MAJOR_VERSION)
list(GET VERSION_LIST 1 OCTOMAP_MINOR_VERSION)
list(GET VERSION_LIST 2 OCTOMAP_PATCH_VERSION)
add_definitions (-DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION}
-DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION}
-DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION})
message(STATUS "FCL uses Octomap")
else()
message(STATUS "FCL does not use Octomap")
endif()
add_definitions (-DFCL_HAVE_OCTOMAP=${FCL_HAVE_OCTOMAP})
ADD_REQUIRED_DEPENDENCY("assimp >= 2.0")
if(ASSIMP_FOUND)
if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150")
......
......@@ -55,7 +55,7 @@ namespace fcl
}
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
#define OCTOMAP_VERSION_AT_LEAST(x,y,z) \
(OCTOMAP_MAJOR_VERSION > x || (OCTOMAP_MAJOR_VERSION >= x && \
(OCTOMAP_MINOR_VERSION > y || (OCTOMAP_MINOR_VERSION >= y && \
......
......@@ -43,7 +43,7 @@
#include <hpp/fcl/traversal/traversal_node_shapes.h>
#include <hpp/fcl/traversal/traversal_node_bvh_shape.h>
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
#include <hpp/fcl/traversal/traversal_node_octree.h>
#endif
......@@ -52,7 +52,7 @@
namespace fcl
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
/// @brief Initialize traversal node for collision between two octrees, given current object transform
template<typename NarrowPhaseSolver>
bool initialize(OcTreeCollisionTraversalNode<NarrowPhaseSolver>& node,
......
......@@ -38,7 +38,7 @@
#include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h>
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
#include <hpp/fcl/octree.h>
#endif
......@@ -51,7 +51,7 @@ namespace details
namespace dynamic_AABB_tree
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, const OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3f& tf2, void* cdata, CollisionCallBack callback)
{
if(!root2)
......@@ -744,7 +744,7 @@ void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* cdata,
if(size() == 0) return;
switch(obj->collisionGeometry()->getNodeType())
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
case GEOM_OCTREE:
{
if(!octree_as_geometry_collide)
......@@ -768,7 +768,7 @@ void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* cdata
FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
switch(obj->collisionGeometry()->getNodeType())
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
case GEOM_OCTREE:
{
if(!octree_as_geometry_distance)
......
......@@ -37,7 +37,7 @@
#include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h>
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
#include <hpp/fcl/octree.h>
#endif
......@@ -50,7 +50,7 @@ namespace details
namespace dynamic_AABB_tree_array
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
bool collisionRecurse_(DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3f& tf2, void* cdata, CollisionCallBack callback)
{
DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root1 = nodes1 + root1_id;
......@@ -631,7 +631,7 @@ bool selfDistanceRecurse(DynamicAABBTreeCollisionManager_Array::DynamicAABBNode*
}
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
bool collisionRecurse(DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3f& tf2, void* cdata, CollisionCallBack callback)
{
if(isQuatIdentity(tf2.getQuatRotation()))
......@@ -769,7 +769,7 @@ void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, void*
if(size() == 0) return;
switch(obj->collisionGeometry()->getNodeType())
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
case GEOM_OCTREE:
{
if(!octree_as_geometry_collide)
......@@ -793,7 +793,7 @@ void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, void*
FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
switch(obj->collisionGeometry()->getNodeType())
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
case GEOM_OCTREE:
{
if(!octree_as_geometry_distance)
......
......@@ -46,7 +46,7 @@
namespace fcl
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
template<typename T_SH, typename NarrowPhaseSolver>
std::size_t ShapeOcTreeCollide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2,
const NarrowPhaseSolver* nsolver,
......@@ -647,7 +647,7 @@ CollisionFunctionMatrix<NarrowPhaseSolver>::CollisionFunctionMatrix()
collision_matrix[BV_kIOS][BV_kIOS] = &BVHCollide<kIOS, NarrowPhaseSolver>;
collision_matrix[BV_OBBRSS][BV_OBBRSS] = &BVHCollide<OBBRSS, NarrowPhaseSolver>;
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
collision_matrix[GEOM_OCTREE][GEOM_BOX] = &OcTreeShapeCollide<Box, NarrowPhaseSolver>;
collision_matrix[GEOM_OCTREE][GEOM_SPHERE] = &OcTreeShapeCollide<Sphere, NarrowPhaseSolver>;
collision_matrix[GEOM_OCTREE][GEOM_CAPSULE] = &OcTreeShapeCollide<Capsule, NarrowPhaseSolver>;
......
......@@ -44,7 +44,7 @@
namespace fcl
{
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
template<typename T_SH, typename NarrowPhaseSolver>
FCL_REAL ShapeOcTreeDistance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const NarrowPhaseSolver* nsolver,
const DistanceRequest& request, DistanceResult& result)
......@@ -450,7 +450,7 @@ DistanceFunctionMatrix<NarrowPhaseSolver>::DistanceFunctionMatrix()
distance_matrix[BV_kIOS][BV_kIOS] = &BVHDistance<kIOS, NarrowPhaseSolver>;
distance_matrix[BV_OBBRSS][BV_OBBRSS] = &BVHDistance<OBBRSS, NarrowPhaseSolver>;
#if FCL_HAVE_OCTOMAP
#ifdef FCL_HAVE_OCTOMAP
distance_matrix[GEOM_OCTREE][GEOM_BOX] = &OcTreeShapeDistance<Box, NarrowPhaseSolver>;
distance_matrix[GEOM_OCTREE][GEOM_SPHERE] = &OcTreeShapeDistance<Sphere, NarrowPhaseSolver>;
distance_matrix[GEOM_OCTREE][GEOM_CAPSULE] = &OcTreeShapeDistance<Capsule, NarrowPhaseSolver>;
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment