From 89661e0518be78b7ca6c998e2c4bee41caef927e Mon Sep 17 00:00:00 2001
From: Justin Carpentier <justin.carpentier@inria.fr>
Date: Mon, 4 Mar 2019 10:18:32 +0100
Subject: [PATCH] all: add missing #ifdef HPP_FCL_HAVE_OCTOMAP

---
 test/CMakeLists.txt       | 4 +++-
 test/test_fcl_utility.cpp | 4 +++-
 test/test_fcl_utility.h   | 9 ++++++++-
 3 files changed, 14 insertions(+), 3 deletions(-)

diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 807e69e7..046d21ae 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -47,7 +47,9 @@ add_fcl_test(test_fcl_profiling test_fcl_profiling.cpp test_fcl_utility.cpp)
 PKG_CONFIG_USE_DEPENDENCY(test_fcl_profiling assimp)
 
 add_fcl_test(test_fcl_gjk test_fcl_gjk.cpp)
-add_fcl_test(test_fcl_octree test_fcl_octree.cpp test_fcl_utility.cpp)
+if(HPP_FCL_HAVE_OCTOMAP)
+  add_fcl_test(test_fcl_octree test_fcl_octree.cpp test_fcl_utility.cpp)
+endif(HPP_FCL_HAVE_OCTOMAP)
 
 ## Benchmark
 add_executable(test-benchmark benchmark.cpp test_fcl_utility.cpp)
diff --git a/test/test_fcl_utility.cpp b/test/test_fcl_utility.cpp
index 7c74bb0f..b60b015d 100644
--- a/test/test_fcl_utility.cpp
+++ b/test/test_fcl_utility.cpp
@@ -209,7 +209,8 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
   os.close();
 }
 
-  OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution)
+#ifdef HPP_FCL_HAVE_OCTOMAP
+OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution)
   {
     std::ifstream file;
     file.open(filename);
@@ -234,6 +235,7 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
     octree->updateInnerOccupancy ();
     return hpp::fcl::OcTree (octree);
   }
+#endif
 
 void eulerToMatrix(FCL_REAL a, FCL_REAL b, FCL_REAL c, Matrix3f& R)
 {
diff --git a/test/test_fcl_utility.h b/test/test_fcl_utility.h
index 08d577a3..80bab48e 100644
--- a/test/test_fcl_utility.h
+++ b/test/test_fcl_utility.h
@@ -41,7 +41,10 @@
 #include <hpp/fcl/math/transform.h>
 #include <hpp/fcl/collision_data.h>
 #include <hpp/fcl/collision_object.h>
+
+#ifdef HPP_FCL_HAVE_OCTOMAP
 #include <hpp/fcl/octree.h>
+#endif
 
 #ifdef _WIN32
 #define NOMINMAX  // required to avoid compilation errors with Visual Studio 2010
@@ -51,9 +54,11 @@
 #endif
 
 
+#ifdef HPP_FCL_HAVE_OCTOMAP
 namespace octomap {
   typedef boost::shared_ptr<OcTree> OcTreePtr_t;
 }
+#endif
 
 namespace hpp
 {
@@ -93,7 +98,9 @@ void loadOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
 
 void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<Triangle>& triangles);
 
- fcl::OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution);
+#ifdef HPP_FCL_HAVE_OCTOMAP
+fcl::OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution);
+#endif
 
 /// @brief Generate one random transform whose translation is constrained by extents and rotation without constraints. 
 /// The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5]
-- 
GitLab