From 5347ca4d1ad7ff122545055da97f8218bc1aa382 Mon Sep 17 00:00:00 2001 From: Justin Carpentier <jcarpent@laas.fr> Date: Tue, 16 Jan 2018 15:36:48 +0100 Subject: [PATCH] [All] Propagate change of FCL_WITH_OCTOMAP definition --- include/hpp/fcl/math/vec_3f.h | 2 +- include/hpp/fcl/traversal/traversal_node_setup.h | 4 ++-- src/broadphase/broadphase_dynamic_AABB_tree.cpp | 8 ++++---- src/broadphase/broadphase_dynamic_AABB_tree_array.cpp | 10 +++++----- src/collision_func_matrix.cpp | 4 ++-- src/distance_func_matrix.cpp | 4 ++-- 6 files changed, 16 insertions(+), 16 deletions(-) diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h index a3568f87..c6590e99 100644 --- a/include/hpp/fcl/math/vec_3f.h +++ b/include/hpp/fcl/math/vec_3f.h @@ -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 && \ diff --git a/include/hpp/fcl/traversal/traversal_node_setup.h b/include/hpp/fcl/traversal/traversal_node_setup.h index bcde2941..5b8a84e2 100644 --- a/include/hpp/fcl/traversal/traversal_node_setup.h +++ b/include/hpp/fcl/traversal/traversal_node_setup.h @@ -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, diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp index fc7ca351..b4a6abaf 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp @@ -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) diff --git a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp index 717452d7..b994e34c 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp @@ -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) diff --git a/src/collision_func_matrix.cpp b/src/collision_func_matrix.cpp index f3f50788..3c13368b 100644 --- a/src/collision_func_matrix.cpp +++ b/src/collision_func_matrix.cpp @@ -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>; diff --git a/src/distance_func_matrix.cpp b/src/distance_func_matrix.cpp index ac7de3f3..19012b31 100644 --- a/src/distance_func_matrix.cpp +++ b/src/distance_func_matrix.cpp @@ -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>; -- GitLab