diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h
index a3568f871e0a4eef0037b7520d5ea1edaa4553e9..c6590e99089a950bc116e6b86f83367829e6e12e 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 bcde2941b043b366f45ffe84135eefb958abc834..5b8a84e2a98b34c02e72b62cff553fd29ba40425 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 fc7ca35174ef1139ff56fb0d0549fdce05f6eafb..b4a6abafde65176c9ae5db5841fdb6e94e13ac33 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 717452d7e199f5fe143b05ca0cf99b033c76074b..b994e34c3abeceef6aca7891db23f10b500b6e8f 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 f3f50788107e2dac61355a0817c39f9aafbef9b8..3c13368b439aa6e7ddd8cd1f7f3ba1803612eb70 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 ac7de3f34aac11b9d50479aaaebf5c93d7e2cb73..19012b312b817e6f53758fe116e02cfea5858af0 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>;