From 30647ad04fd3dfabf03463f9587e726510ab75ee Mon Sep 17 00:00:00 2001
From: Valenza Florian <fvalenza@laas.fr>
Date: Mon, 1 Aug 2016 14:32:00 +0200
Subject: [PATCH] [C++][CMake] Merged fake-fcl with fcl.hpp (splitted in .hpp
 and .hxx file). Propagated flag -DWITH_HPP_FCL to all binaries

---
 CMakeLists.txt                |  4 +-
 benchmark/CMakeLists.txt      |  5 ++
 src/CMakeLists.txt            |  2 -
 src/multibody/fake-fcl.hpp    | 43 -----------------
 src/multibody/fcl.hpp         | 67 +++++++++++++--------------
 src/multibody/fcl.hxx         | 87 +++++++++++++++++++++++++++++++++++
 src/parsers/urdf/geometry.cpp |  2 +
 src/python/python.cpp         |  4 --
 unittest/CMakeLists.txt       | 10 +++-
 utils/CMakeLists.txt          |  3 +-
 10 files changed, 136 insertions(+), 91 deletions(-)
 delete mode 100644 src/multibody/fake-fcl.hpp
 create mode 100644 src/multibody/fcl.hxx

diff --git a/CMakeLists.txt b/CMakeLists.txt
index f71a7a523..3ab5ef5ee 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -249,6 +249,7 @@ ENDIF(URDFDOM_FOUND)
 
 LIST(APPEND ${PROJECT_NAME}_MULTIBODY_HEADERS
   multibody/fcl.hpp
+  multibody/fcl.hxx
   multibody/geometry.hpp
   multibody/geometry.hxx
   )
@@ -260,9 +261,6 @@ IF(HPP_FCL_FOUND)
   LIST(APPEND ${PROJECT_NAME}_SPATIAL_HEADERS
     spatial/fcl-pinocchio-conversions.hpp
     )
-ELSE(HPP_FCL_FOUND)
-  LIST(APPEND ${PROJECT_NAME}_MULTIBODY_HEADERS
-       multibody/fake-fcl.hpp)
 ENDIF(HPP_FCL_FOUND)
 
 IF(LUA5_1_FOUND)
diff --git a/benchmark/CMakeLists.txt b/benchmark/CMakeLists.txt
index bf1b0d56b..1d254b4ec 100644
--- a/benchmark/CMakeLists.txt
+++ b/benchmark/CMakeLists.txt
@@ -37,6 +37,10 @@ ENDIF(BUILD_PYTHON_INTERFACE)
 IF(${URDFDOM_FOUND})
   PKG_CONFIG_USE_DEPENDENCY(timings urdfdom)
 ENDIF(${URDFDOM_FOUND})
+IF(HPP_FCL_FOUND)
+  PKG_CONFIG_USE_DEPENDENCY(timings hpp-fcl)
+  ADD_TEST_CFLAGS(timings "-DWITH_HPP_FCL")
+ENDIF(HPP_FCL_FOUND)
 SET_TARGET_PROPERTIES (timings PROPERTIES COMPILE_DEFINITIONS PINOCCHIO_SOURCE_DIR="${${PROJECT_NAME}_SOURCE_DIR}")
 
 # timings-eigen
@@ -48,6 +52,7 @@ ELSE(BUILD_BENCHMARK)
 ENDIF(BUILD_BENCHMARK)
 PKG_CONFIG_USE_DEPENDENCY(timings-eigen eigen3)
 
+
 # geomTimings
 # 
 IF(URDFDOM_FOUND AND HPP_FCL_FOUND)
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 28d4e58ad..9eee54a07 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -62,11 +62,9 @@ IF(URDFDOM_FOUND)
     parsers/urdf/model.cpp
     )
 
-  IF(HPP_FCL_FOUND)
     LIST(APPEND ${PROJECT_NAME}_PARSERS_SOURCES
       parsers/urdf/geometry.cpp
       )
-  ENDIF(HPP_FCL_FOUND)
 ENDIF(URDFDOM_FOUND)
 
 IF(LUA5_1_FOUND)
diff --git a/src/multibody/fake-fcl.hpp b/src/multibody/fake-fcl.hpp
deleted file mode 100644
index 6290c77ca..000000000
--- a/src/multibody/fake-fcl.hpp
+++ /dev/null
@@ -1,43 +0,0 @@
-//
-// Copyright (c) 2016 CNRS
-//
-// This file is part of Pinocchio
-// Pinocchio is free software: you can redistribute it
-// and/or modify it under the terms of the GNU Lesser General Public
-// License as published by the Free Software Foundation, either version
-// 3 of the License, or (at your option) any later version.
-//
-// Pinocchio is distributed in the hope that it will be
-// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
-// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
-// General Lesser Public License for more details. You should have
-// received a copy of the GNU Lesser General Public License along with
-// Pinocchio If not, see
-// <http://www.gnu.org/licenses/>.
-
-#ifndef __se3_fake_fcl_hpp__
-#define __se3_fake_fcl_hpp__
-
-
-namespace se3
-{
-  namespace fcl
-  {
- 
-    struct FakeCollisionGeometry
-    {
-      FakeCollisionGeometry(){};
-    };
-
-    struct AABB
-    {
-      AABB(): min_(0), max_(1){};
-
-      int min_;
-      int max_;
-    };
-    typedef FakeCollisionGeometry CollisionGeometry;
-
-  }
-}
-#endif // __se3_fake_fcl_hpp__
diff --git a/src/multibody/fcl.hpp b/src/multibody/fcl.hpp
index 9730358ca..0ba8b92ac 100644
--- a/src/multibody/fcl.hpp
+++ b/src/multibody/fcl.hpp
@@ -19,15 +19,13 @@
 #define __se3_fcl_hpp__
 
 #include "pinocchio/multibody/fwd.hpp"
-#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
 
 #ifdef WITH_HPP_FCL
 #include <hpp/fcl/collision_object.h>
 #include <hpp/fcl/collision.h>
 #include <hpp/fcl/distance.h>
 #include <hpp/fcl/shape/geometric_shapes.h>
-#else
-#include "pinocchio/multibody/fake-fcl.hpp"
+#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
 #endif
 
 #include <iostream>
@@ -37,6 +35,7 @@
 #include <assert.h>
 
 #include <boost/foreach.hpp>
+#include <boost/shared_ptr.hpp>
 
 namespace se3
 {
@@ -64,10 +63,8 @@ namespace se3
     }
     
     void disp(std::ostream & os) const { os << "collision pair (" << first << "," << second << ")\n"; }
-    friend std::ostream & operator << (std::ostream & os, const CollisionPair & X)
-    {
-      X.disp(os); return os;
-    }
+    friend std::ostream & operator << (std::ostream & os, const CollisionPair & X);
+
   }; // struct CollisionPair
   typedef std::vector<CollisionPair> CollisionPairsVector_t;
 
@@ -87,17 +84,17 @@ namespace se3
     ///
     /// @brief Return the minimal distance between two geometry objects
     ///
-    double distance () const { return fcl_distance_result.min_distance; }
+    double distance () const;
 
     ///
     /// \brief Return the witness point on the inner object expressed in global frame.
     ///
-    Eigen::Vector3d closestPointInner () const { return toVector3d(fcl_distance_result.nearest_points [0]); }
+    Eigen::Vector3d closestPointInner () const;
     
     ///
     /// \brief Return the witness point on the outer object expressed in global frame.
     ///
-    Eigen::Vector3d closestPointOuter () const { return toVector3d(fcl_distance_result.nearest_points [1]); }
+    Eigen::Vector3d closestPointOuter () const;
     
     bool operator == (const DistanceResult & other) const
     {
@@ -156,14 +153,29 @@ namespace se3
 
   }; // struct CollisionResult
 
-/// \brief Return true if the intrinsic geometry of the two CollisionObject is the same
-inline bool operator == (const fcl::CollisionObject & lhs, const fcl::CollisionObject & rhs)
-{
-  return lhs.collisionGeometry() == rhs.collisionGeometry()
-          && lhs.getAABB().min_ == rhs.getAABB().min_
-          && lhs.getAABB().max_ == rhs.getAABB().max_;
-}
+#else
+
+  namespace fcl
+  {
+ 
+    struct FakeCollisionGeometry
+    {
+      FakeCollisionGeometry(){};
+    };
+
+    struct AABB
+    {
+      AABB(): min_(0), max_(1){};
+
+      int min_;
+      int max_;
+    };
+    typedef FakeCollisionGeometry CollisionGeometry;
+
+  }
+
 #endif // WITH_HPP_FCL
+
 enum GeometryType
 {
   VISUAL,
@@ -209,28 +221,10 @@ struct GeometryObject
     return *this;
   }
 
+  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geom_object);
 };
   
-  inline bool operator==(const GeometryObject & lhs, const GeometryObject & rhs)
-  {
-    return ( lhs.name == rhs.name
-            && lhs.parent == rhs.parent
-            && lhs.collision_geometry == rhs.collision_geometry
-            && lhs.placement == rhs.placement
-            && lhs.mesh_path ==  rhs.mesh_path
-            );
-  }
 
-  inline std::ostream & operator<< (std::ostream & os, const GeometryObject & geom_object)
-  {
-    os  << "Name: \t \n" << geom_object.name << "\n"
-        << "Parent ID: \t \n" << geom_object.parent << "\n"
-        // << "collision object: \t \n" << geom_object.collision_geometry << "\n"
-        << "Position in parent frame: \t \n" << geom_object.placement << "\n"
-        << "Absolute path to mesh file: \t \n" << geom_object.mesh_path << "\n"
-        << std::endl;
-    return os;
-  }
 
 
 } // namespace se3
@@ -238,6 +232,7 @@ struct GeometryObject
 /* --- Details -------------------------------------------------------------- */
 /* --- Details -------------------------------------------------------------- */
 /* --- Details -------------------------------------------------------------- */
+#include "pinocchio/multibody/fcl.hxx"
 
 
 #endif // ifndef __se3_fcl_hpp__
diff --git a/src/multibody/fcl.hxx b/src/multibody/fcl.hxx
new file mode 100644
index 000000000..4a5a4070b
--- /dev/null
+++ b/src/multibody/fcl.hxx
@@ -0,0 +1,87 @@
+//
+// Copyright (c) 2015-2016 CNRS
+//
+// This file is part of Pinocchio
+// Pinocchio is free software: you can redistribute it
+// and/or modify it under the terms of the GNU Lesser General Public
+// License as published by the Free Software Foundation, either version
+// 3 of the License, or (at your option) any later version.
+//
+// Pinocchio is distributed in the hope that it will be
+// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
+// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+// General Lesser Public License for more details. You should have
+// received a copy of the GNU Lesser General Public License along with
+// Pinocchio If not, see
+// <http://www.gnu.org/licenses/>.
+
+#ifndef __se3_fcl_hxx__
+#define __se3_fcl_hxx__
+
+
+#include <iostream>
+
+
+namespace se3
+{
+
+  inline std::ostream & operator << (std::ostream & os, const CollisionPair & X)
+  {
+    X.disp(os); return os;
+  } 
+  
+
+#ifdef WITH_HPP_FCL  
+
+
+  inline double DistanceResult::distance () const
+  {
+    return fcl_distance_result.min_distance;
+  }
+
+  inline Eigen::Vector3d DistanceResult::closestPointInner () const
+  {
+    return toVector3d(fcl_distance_result.nearest_points [0]);
+  }
+
+  inline Eigen::Vector3d DistanceResult::closestPointOuter () const
+  {
+    return toVector3d(fcl_distance_result.nearest_points [1]);
+  }
+    
+  inline bool operator == (const fcl::CollisionObject & lhs, const fcl::CollisionObject & rhs)
+  {
+    return lhs.collisionGeometry() == rhs.collisionGeometry()
+            && lhs.getAABB().min_ == rhs.getAABB().min_
+            && lhs.getAABB().max_ == rhs.getAABB().max_;
+  }
+  
+#endif // WITH_HPP_FCL
+
+  
+  inline bool operator==(const GeometryObject & lhs, const GeometryObject & rhs)
+  {
+    return ( lhs.name == rhs.name
+            && lhs.parent == rhs.parent
+            && lhs.collision_geometry == rhs.collision_geometry
+            && lhs.placement == rhs.placement
+            && lhs.mesh_path ==  rhs.mesh_path
+            );
+  }
+
+  inline std::ostream & operator<< (std::ostream & os, const GeometryObject & geom_object)
+  {
+    os  << "Name: \t \n" << geom_object.name << "\n"
+        << "Parent ID: \t \n" << geom_object.parent << "\n"
+        // << "collision object: \t \n" << geom_object.collision_geometry << "\n"
+        << "Position in parent frame: \t \n" << geom_object.placement << "\n"
+        << "Absolute path to mesh file: \t \n" << geom_object.mesh_path << "\n"
+        << std::endl;
+    return os;
+  }
+
+
+} // namespace se3
+
+
+#endif // ifndef __se3_fcl_hxx__
diff --git a/src/parsers/urdf/geometry.cpp b/src/parsers/urdf/geometry.cpp
index e5e2c15d7..be790cb0e 100644
--- a/src/parsers/urdf/geometry.cpp
+++ b/src/parsers/urdf/geometry.cpp
@@ -28,7 +28,9 @@
 #include <iomanip>
 #include <boost/foreach.hpp>
 
+#ifdef WITH_HPP_FCL
 #include <hpp/fcl/mesh_loader/assimp.h>
+#endif // WITH_HPP_FCL
 
 namespace se3
 {
diff --git a/src/python/python.cpp b/src/python/python.cpp
index cad794b90..bb42329b8 100644
--- a/src/python/python.cpp
+++ b/src/python/python.cpp
@@ -32,11 +32,9 @@
 #include "pinocchio/python/parsers.hpp"
 #include "pinocchio/python/explog.hpp"
 
-#ifdef WITH_HPP_FCL
 #include "pinocchio/python/geometry-object.hpp"
 #include "pinocchio/python/geometry-model.hpp"
 #include "pinocchio/python/geometry-data.hpp"
-#endif
 
 namespace se3
 {
@@ -74,12 +72,10 @@ namespace se3
       FramePythonVisitor::expose();
       ModelPythonVisitor::expose();
       DataPythonVisitor::expose();
-#ifdef WITH_HPP_FCL
       GeometryObjectPythonVisitor::expose();      
       CollisionPairPythonVisitor::expose();
       GeometryModelPythonVisitor::expose();
       GeometryDataPythonVisitor::expose();
-#endif      
     }
     void exposeAlgorithms()
     {
diff --git a/unittest/CMakeLists.txt b/unittest/CMakeLists.txt
index f3615c35b..a9798562b 100644
--- a/unittest/CMakeLists.txt
+++ b/unittest/CMakeLists.txt
@@ -28,8 +28,15 @@ MACRO(ADD_UNIT_TEST NAME PKGS)
     PKG_CONFIG_USE_DEPENDENCY(${NAME} ${PKG})
   ENDFOREACH(PKG)
 
+  IF(HPP_FCL_FOUND)
+    PKG_CONFIG_USE_DEPENDENCY(${NAME} hpp-fcl)
+    ADD_TEST_CFLAGS(${NAME} "-DWITH_HPP_FCL")
+  ENDIF(HPP_FCL_FOUND)
+
   TARGET_LINK_LIBRARIES(${NAME} ${PROJECT_NAME})
+
   IF(BUILD_PYTHON_INTERFACE)
+    TARGET_LINK_BOOST_PYTHON(${NAME})
     TARGET_LINK_LIBRARIES(${NAME} ${PYTHON_LIBRARIES})
   ENDIF(BUILD_PYTHON_INTERFACE)
 
@@ -68,9 +75,8 @@ IF(URDFDOM_FOUND)
   ADD_UNIT_TEST(value "eigen3;urdfdom")
   ADD_TEST_CFLAGS(value '-DPINOCCHIO_SOURCE_DIR=\\\"${${PROJECT_NAME}_SOURCE_DIR}\\\"')
   IF(HPP_FCL_FOUND)
-    ADD_UNIT_TEST(geom "eigen3;urdfdom;hpp-fcl")
+    ADD_UNIT_TEST(geom "eigen3;urdfdom")
     ADD_TEST_CFLAGS(geom '-DPINOCCHIO_SOURCE_DIR=\\\"${${PROJECT_NAME}_SOURCE_DIR}\\\"')
-    ADD_TEST_CFLAGS(geom "-DWITH_HPP_FCL")
     IF(BUILD_TESTS_WITH_HPP)
       ADD_OPTIONAL_DEPENDENCY("hpp-model-urdf")
       IF(HPP_MODEL_URDF_FOUND)
diff --git a/utils/CMakeLists.txt b/utils/CMakeLists.txt
index 66faac413..66bbd3571 100644
--- a/utils/CMakeLists.txt
+++ b/utils/CMakeLists.txt
@@ -38,7 +38,8 @@ MACRO(ADD_UTIL NAME UTIL_SRC PKGS)
 
   IF(BUILD_UTILS)
     INSTALL(TARGETS ${NAME} DESTINATION bin)
-  ENDIF(BUILD_UTILS)
+  ENDIF(BUILD_UTILS) 
+
 
 ENDMACRO(ADD_UTIL)
 
-- 
GitLab