From 8aa94d0baaf715bb49e5fb43d9ad88c73b296941 Mon Sep 17 00:00:00 2001
From: Joseph Mirabel <jmirabel@laas.fr>
Date: Thu, 31 Jan 2019 21:50:26 +0100
Subject: [PATCH] Prefix HPP_ for preprocessor variables.

---
 CMakeLists.txt                                | 34 ++++++++++---------
 include/hpp/fcl/math/vec_3f.h                 |  4 +--
 include/hpp/fcl/mesh_loader/assimp.h          |  4 +--
 .../hpp/fcl/traversal/traversal_node_setup.h  |  4 +--
 src/collision_func_matrix.cpp                 |  4 +--
 src/distance_func_matrix.cpp                  |  4 +--
 6 files changed, 28 insertions(+), 26 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 1037f4f6..7ae56c06 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -76,10 +76,10 @@ search_for_boost()
 # Optional dependencies
 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 TRUE)
-  add_definitions (-DFCL_HAVE_OCTOMAP)
+  include_directories(${OCTOMAP_INCLUDE_DIRS})
+  link_directories(${OCTOMAP_LIBRARY_DIRS})
+  SET(HPP_FCL_HAVE_OCTOMAP TRUE)
+  add_definitions (-DHPP_FCL_HAVE_OCTOMAP)
   string(REPLACE "." ";" VERSION_LIST ${OCTOMAP_VERSION})
   list(GET VERSION_LIST 0 OCTOMAP_MAJOR_VERSION)
   list(GET VERSION_LIST 1 OCTOMAP_MINOR_VERSION)
@@ -87,20 +87,20 @@ if (OCTOMAP_INCLUDE_DIRS AND OCTOMAP_LIBRARY_DIRS)
   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")
+  message(STATUS "FCL uses Octomap")
 else()
-  SET(FCL_HAVE_OCTOMAP FALSE)
-	message(STATUS "FCL does not use Octomap")
+  SET(HPP_FCL_HAVE_OCTOMAP FALSE)
+  message(STATUS "FCL does not use Octomap")
 endif()
 
 ADD_REQUIRED_DEPENDENCY("assimp >= 2.0")
 if(ASSIMP_FOUND)
   if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150")
-    add_definitions(-DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
-    SET(WITH_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES TRUE)
+    add_definitions(-DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
+    SET(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES TRUE)
     message(STATUS "Assimp version has unified headers")
   else()
-    SET(WITH_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES FALSE)
+    SET(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES FALSE)
     message(STATUS "Assimp version does not have unified headers")
   endif()
 endif()
@@ -162,12 +162,14 @@ endif ()
 
 pkg_config_append_libs("hpp-fcl")
 PKG_CONFIG_APPEND_BOOST_LIBS(thread date_time filesystem system)
-IF(WITH_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
-  PKG_CONFIG_APPEND_CFLAGS("-DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES")
-ENDIF(WITH_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
-IF(FCL_HAVE_OCTOMAP)
+IF(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
+  # FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES kept for backard compatibility reasons.
+  PKG_CONFIG_APPEND_CFLAGS("-DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES")
+ENDIF(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
+IF(HPP_FCL_HAVE_OCTOMAP)
+  # FCL_HAVE_OCTOMAP kept for backward compatibility reasons.
   PKG_CONFIG_APPEND_CFLAGS(
-    "-DFCL_HAVE_OCTOMAP -DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION} -DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION} -DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION}")
-ENDIF(FCL_HAVE_OCTOMAP)
+    "-DHPP_FCL_HAVE_OCTOMAP -DFCL_HAVE_OCTOMAP -DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION} -DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION} -DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION}")
+ENDIF(HPP_FCL_HAVE_OCTOMAP)
 
 setup_project_finalize()
diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h
index ede7b017..b7fcef9d 100644
--- a/include/hpp/fcl/math/vec_3f.h
+++ b/include/hpp/fcl/math/vec_3f.h
@@ -57,7 +57,7 @@ namespace fcl
 }
 
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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 && \
@@ -67,7 +67,7 @@ namespace fcl
     (OCTOMAP_MAJOR_VERSION < x || (OCTOMAP_MAJOR_VERSION <= x && \
     (OCTOMAP_MINOR_VERSION < y || (OCTOMAP_MINOR_VERSION <= y && \
     OCTOMAP_PATCH_VERSION <= z))))
-#endif // FCL_HAVE_OCTOMAP
+#endif // HPP_FCL_HAVE_OCTOMAP
 
 } // namespace hpp
 
diff --git a/include/hpp/fcl/mesh_loader/assimp.h b/include/hpp/fcl/mesh_loader/assimp.h
index 12f6a631..8f0bce65 100644
--- a/include/hpp/fcl/mesh_loader/assimp.h
+++ b/include/hpp/fcl/mesh_loader/assimp.h
@@ -37,7 +37,7 @@
 #ifndef HPP_FCL_MESH_LOADER_ASSIMP_H
 #define HPP_FCL_MESH_LOADER_ASSIMP_H
 
-#ifdef FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
+#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
   #include <assimp/DefaultLogger.hpp>
   #include <assimp/IOStream.hpp>
   #include <assimp/IOSystem.hpp>
@@ -166,7 +166,7 @@ inline void buildMesh (const fcl::Vec3f & scale,
       aiFace& face = input_mesh->mFaces[j];
       if (face.mNumIndices != 3) {
         std::stringstream ss;
-#ifdef FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
+#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
         ss << "Mesh " << input_mesh->mName.C_Str() << " has a face with "
            << face.mNumIndices << " vertices. This is not supported\n";
         ss << "Node name is: " << node->mName.C_Str() << "\n";
diff --git a/include/hpp/fcl/traversal/traversal_node_setup.h b/include/hpp/fcl/traversal/traversal_node_setup.h
index b58ea457..041b3fa6 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>
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_FCL_HAVE_OCTOMAP
 #include <hpp/fcl/traversal/traversal_node_octree.h>
 #endif
 
@@ -54,7 +54,7 @@ namespace hpp
 namespace fcl
 {
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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/collision_func_matrix.cpp b/src/collision_func_matrix.cpp
index 68a3120b..7a7a6fba 100644
--- a/src/collision_func_matrix.cpp
+++ b/src/collision_func_matrix.cpp
@@ -48,7 +48,7 @@ namespace hpp
 namespace fcl
 {
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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,
@@ -505,7 +505,7 @@ CollisionFunctionMatrix<NarrowPhaseSolver>::CollisionFunctionMatrix()
   collision_matrix[BV_kIOS][BV_kIOS] = &BVHCollide<kIOS, NarrowPhaseSolver>;
   collision_matrix[BV_OBBRSS][BV_OBBRSS] = &BVHCollide<OBBRSS, NarrowPhaseSolver>;
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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 3b31a59c..c83148c0 100644
--- a/src/distance_func_matrix.cpp
+++ b/src/distance_func_matrix.cpp
@@ -46,7 +46,7 @@ namespace hpp
 namespace fcl
 {
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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)
@@ -452,7 +452,7 @@ DistanceFunctionMatrix<NarrowPhaseSolver>::DistanceFunctionMatrix()
   distance_matrix[BV_kIOS][BV_kIOS] = &BVHDistance<kIOS, NarrowPhaseSolver>;
   distance_matrix[BV_OBBRSS][BV_OBBRSS] = &BVHDistance<OBBRSS, NarrowPhaseSolver>;
 
-#ifdef FCL_HAVE_OCTOMAP
+#ifdef HPP_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