diff --git a/CMakeLists.txt b/CMakeLists.txt
index aa6b020e6c0d91dce253d0974c247c543926ce43..86633b85fbadfb90ce81980340c299f7eb9b9e03 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -41,6 +41,9 @@ set(PROJECT_DESCRIPTION
   )
 SET(PROJECT_USE_CMAKE_EXPORT TRUE)
 
+SET(CMAKE_C_STANDARD 99)
+SET(CMAKE_CXX_STANDARD 98)
+
 # Do not support CMake older than 2.8.12
 CMAKE_POLICY(SET CMP0022 NEW)
 SET(PROJECT_USE_KEYWORD_LINK_LIBRARIES TRUE)
@@ -55,6 +58,7 @@ include(cmake/boost.cmake)
 include(cmake/python.cmake)
 include(cmake/hpp.cmake)
 include(cmake/apple.cmake)
+include(cmake/ide.cmake)
 
 # If needed, fix CMake policy for APPLE systems
 APPLY_DEFAULT_APPLE_CONFIGURATION()
diff --git a/cmake b/cmake
index 308d3c947a3e276b06c5fa79894119346635de4d..a99dc925bde7b976ae1ed286d0ab38906c73dff5 160000
--- a/cmake
+++ b/cmake
@@ -1 +1 @@
-Subproject commit 308d3c947a3e276b06c5fa79894119346635de4d
+Subproject commit a99dc925bde7b976ae1ed286d0ab38906c73dff5
diff --git a/include/hpp/fcl/BV/AABB.h b/include/hpp/fcl/BV/AABB.h
index 55a5e4adb92a73b9d2b8416c487b1075a8bac831..d79f76fefd86796bfd24a11e39bde23223a883e2 100644
--- a/include/hpp/fcl/BV/AABB.h
+++ b/include/hpp/fcl/BV/AABB.h
@@ -38,14 +38,15 @@
 #ifndef HPP_FCL_AABB_H
 #define HPP_FCL_AABB_H
 
-#include <stdexcept>
 #include <hpp/fcl/data_types.h>
 
 namespace hpp
 {
 namespace fcl
 {
-  class CollisionRequest;
+
+struct CollisionRequest;
+
 /// @defgroup Bounding_Volume 
 /// regroup class of differents types of bounding volume.
 /// @{
diff --git a/include/hpp/fcl/BV/BV.h b/include/hpp/fcl/BV/BV.h
index 238ec16bfc416c9235741900d1f28c9577b931d2..ba042f40402af2c3ea382703b4eb78f8fcc9c26c 100644
--- a/include/hpp/fcl/BV/BV.h
+++ b/include/hpp/fcl/BV/BV.h
@@ -62,7 +62,7 @@ template<typename BV1, typename BV2>
 class Converter
 {
 private:
-  static void convert(const BV1& bv1, const Transform3f& tf1, BV2& bv2)
+  static void convert(const BV1& /*bv1*/, const Transform3f& /*tf1*/, BV2& /*bv2*/)
   {
     // should only use the specialized version, so it is private.
   }
diff --git a/include/hpp/fcl/BV/BV_node.h b/include/hpp/fcl/BV/BV_node.h
index 86e858f2f40b5da2857b229ceb9e8b6d13f32985..901a9fcb1f6d9035200a165d99af10fbaf7b4a6a 100644
--- a/include/hpp/fcl/BV/BV_node.h
+++ b/include/hpp/fcl/BV/BV_node.h
@@ -107,11 +107,15 @@ struct BVNode : public BVNodeBase
     return bv.distance(other.bv, P1, P2);
   }
 
-  /// @brief Access the center of the BV
+  /// @brief Access to the center of the BV
   Vec3f getCenter() const { return bv.center(); }
 
-  /// @brief Access the orientation of the BV
-  const Matrix3f& getOrientation() const { return Matrix3f::Identity(); }
+  /// @brief Access to the orientation of the BV
+  const Matrix3f& getOrientation() const
+  {
+    static const Matrix3f id3 = Matrix3f::Identity();
+    return id3;
+  }
 };
 
 template<>
diff --git a/include/hpp/fcl/BV/OBB.h b/include/hpp/fcl/BV/OBB.h
index 32468de639bbef10eea0ac63c1b873e4b5d583ae..02a242ee8a77ce0cd1257b4be90abf57443e1576 100644
--- a/include/hpp/fcl/BV/OBB.h
+++ b/include/hpp/fcl/BV/OBB.h
@@ -44,7 +44,8 @@ namespace hpp
 {
 namespace fcl
 {
-  class CollisionRequest;
+
+struct CollisionRequest;
 
 /// @addtogroup Bounding_Volume
 /// @{
diff --git a/include/hpp/fcl/BV/OBBRSS.h b/include/hpp/fcl/BV/OBBRSS.h
index def7ce67ddd35cc54d5bd654acdeb8c138b5622f..e7ef5c7edfb926eebe896d343a2126ba9bf66835 100644
--- a/include/hpp/fcl/BV/OBBRSS.h
+++ b/include/hpp/fcl/BV/OBBRSS.h
@@ -46,7 +46,8 @@ namespace hpp
 {
 namespace fcl
 {
-  class CollisionRequest;
+
+  struct CollisionRequest;
 
 /// @addtogroup Bounding_Volume
 /// @{
diff --git a/include/hpp/fcl/BV/RSS.h b/include/hpp/fcl/BV/RSS.h
index a380de68c2b033bda110b5bee23d1dfa679058bb..bca8437832151f823690cd2c11f861c52c1674e8 100644
--- a/include/hpp/fcl/BV/RSS.h
+++ b/include/hpp/fcl/BV/RSS.h
@@ -38,7 +38,6 @@
 #ifndef HPP_FCL_RSS_H
 #define HPP_FCL_RSS_H
 
-#include <stdexcept>
 #include <hpp/fcl/data_types.h>
 #include <boost/math/constants/constants.hpp>
 
@@ -47,7 +46,8 @@ namespace hpp
 namespace fcl
 {
 
-  class CollisionRequest;
+struct CollisionRequest;
+
 /// @addtogroup Bounding_Volume
 /// @{
 
@@ -164,4 +164,4 @@ bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1, const RSS& b2,
 
 } // namespace hpp
 
-#endif
\ No newline at end of file
+#endif
diff --git a/include/hpp/fcl/BV/kDOP.h b/include/hpp/fcl/BV/kDOP.h
index 6a5c6aabe88b7a3a8cb6398ef2365b8d41d0119f..3293be7117921de97cbc5497c478881673a75676 100644
--- a/include/hpp/fcl/BV/kDOP.h
+++ b/include/hpp/fcl/BV/kDOP.h
@@ -46,7 +46,7 @@ namespace hpp
 namespace fcl
 {
 
-  class CollisionRequest;
+struct CollisionRequest;
 
   /// @addtogroup Bounding_Volume
   /// @{
diff --git a/include/hpp/fcl/BV/kIOS.h b/include/hpp/fcl/BV/kIOS.h
index be1a4f0bb0d050646ed287c66245f940d43f3d3a..3ecad0cd21ef6632effc311dd42730afb4bb47c0 100644
--- a/include/hpp/fcl/BV/kIOS.h
+++ b/include/hpp/fcl/BV/kIOS.h
@@ -45,7 +45,8 @@ namespace hpp
 {
 namespace fcl
 {
-  class CollisionRequest;
+
+struct CollisionRequest;
 
 /// @addtogroup Bounding_Volume
 /// @{
diff --git a/include/hpp/fcl/collision_data.h b/include/hpp/fcl/collision_data.h
index fdc9993acfe47bfe90f40230b8f9cb1730c8b0ec..db61106193549b0d2af496c562fe01dd42ed2782 100644
--- a/include/hpp/fcl/collision_data.h
+++ b/include/hpp/fcl/collision_data.h
@@ -129,6 +129,11 @@ struct Contact
             && pos == other.pos
             && penetration_depth == other.penetration_depth;
   }
+  
+  bool operator != (const Contact& other) const
+  {
+    return !(*this == other);
+  }
 };
 
 struct CollisionResult;
diff --git a/include/hpp/fcl/internal/tools.h b/include/hpp/fcl/internal/tools.h
index 8ad8a7abc3d1b82df20d475fafdfb2b14057972a..e8c89a1dde94f91fa6e34ca6b499e93ef156feba 100644
--- a/include/hpp/fcl/internal/tools.h
+++ b/include/hpp/fcl/internal/tools.h
@@ -206,4 +206,5 @@ bool isEqual(const Eigen::MatrixBase<Derived>& lhs, const Eigen::MatrixBase<Othe
 }
 } // namespace hpp
 
-#endif
\ No newline at end of file
+#endif
+
diff --git a/include/hpp/fcl/internal/traversal_node_base.h b/include/hpp/fcl/internal/traversal_node_base.h
index 6f6c41e32afcd3ddfbf79a11a32a6fefab5eab15..8c5fcadb5befdda376cd37ffd9eb16d437498174 100644
--- a/include/hpp/fcl/internal/traversal_node_base.h
+++ b/include/hpp/fcl/internal/traversal_node_base.h
@@ -181,4 +181,5 @@ public:
 
 /// @endcond
 
-#endif
\ No newline at end of file
+#endif
+
diff --git a/include/hpp/fcl/math/transform.h b/include/hpp/fcl/math/transform.h
index dd6e9f4cbaeb197d17742d7bfef4adc520b712e7..0ccced3711b018445312567d2543547d68ee6002 100644
--- a/include/hpp/fcl/math/transform.h
+++ b/include/hpp/fcl/math/transform.h
@@ -55,17 +55,6 @@ static inline std::ostream& operator << (std::ostream& o, const Quaternion3f& q)
   return o;
 }
 
-inline bool isQuatIdentity (const Quaternion3f& q)
-{
-  return (q.w() == 1 || q.w() == -1) && q.x() == 0 && q.y() == 0 && q.z() == 0;
-}
-
-inline bool areQuatEquals (const Quaternion3f& q1, const Quaternion3f& q2)
-{
-  return (q1.w() ==  q2.w() && q1.x() ==  q2.x() && q1.y() ==  q2.y() && q1.z() ==  q2.z())
-      || (q1.w() == -q2.w() && q1.x() == -q2.x() && q1.y() == -q2.y() && q1.z() == -q2.z());
-}
-
 /// @brief Simple transform class used locally by InterpMotion
 class Transform3f
 {
@@ -140,8 +129,9 @@ public:
   }
 
   /// @brief set transform from rotation and translation
-  template <typename Matrixx3Like, typename Vector3Like>
-  inline void setTransform(const Eigen::MatrixBase<Matrixx3Like>& R_, const Eigen::MatrixBase<Vector3Like>& T_)
+  template <typename Matrix3Like, typename Vector3Like>
+  inline void setTransform(const Eigen::MatrixBase<Matrix3Like>& R_,
+                           const Eigen::MatrixBase<Vector3Like>& T_)
   {
     R.noalias() = R_;
     T.noalias() = T_;
@@ -242,7 +232,7 @@ public:
 template<typename Derived>
 inline Quaternion3f fromAxisAngle(const Eigen::MatrixBase<Derived>& axis, FCL_REAL angle)
 {
-  return Quaternion3f (Eigen::AngleAxis<double>(angle, axis));
+  return Quaternion3f (Eigen::AngleAxis<FCL_REAL>(angle, axis));
 }
 
 }
diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt
index cfccdedc2ac8aa3a5c5d3ed221cfd55eaaa4a487..b759d6abc8941fd38e3d9f472b91557943a7f9bc 100644
--- a/python/CMakeLists.txt
+++ b/python/CMakeLists.txt
@@ -39,13 +39,22 @@ SET(LIBRARY_NAME hppfcl)
 
 INCLUDE_DIRECTORIES("${Boost_INCLUDE_DIRS}" ${PYTHON_INCLUDE_DIRS})
 
-ADD_LIBRARY(${LIBRARY_NAME} SHARED
+SET(${LIBRARY_NAME}_HEADERS
+  fcl.hh
+  ) 
+
+SET(${LIBRARY_NAME}_SOURCES
   version.cc
   math.cc
   collision-geometries.cc
   collision.cc
   distance.cc
-  fcl.cc)
+  fcl.cc
+  )
+
+ADD_LIBRARY(${LIBRARY_NAME} SHARED ${${LIBRARY_NAME}_SOURCES} ${${LIBRARY_NAME}_HEADERS})
+ADD_HEADER_GROUP(${LIBRARY_NAME}_HEADER)
+ADD_SOURCE_GROUP(${LIBRARY_NAME}_SOURCES)
 
 TARGET_LINK_BOOST_PYTHON(${LIBRARY_NAME} PUBLIC)
 TARGET_LINK_LIBRARIES(${LIBRARY_NAME} PUBLIC ${PROJECT_NAME} ${BOOST_system_LIBRARY})
diff --git a/python/collision-geometries.cc b/python/collision-geometries.cc
index fc604318acd9736acdf852c41dd401b748700d40..80b5fb7389cf441666b9bc89447f7ffdf658878e 100644
--- a/python/collision-geometries.cc
+++ b/python/collision-geometries.cc
@@ -1,7 +1,7 @@
 //
 // Software License Agreement (BSD License)
 //
-//  Copyright (c) 2019 CNRS-LAAS
+//  Copyright (c) 2019 CNRS-LAAS INRIA
 //  Author: Joseph Mirabel
 //  All rights reserved.
 //
@@ -34,6 +34,8 @@
 
 #include <boost/python.hpp>
 
+#include <eigenpy/registration.hpp>
+
 #include "fcl.hh"
 
 #include <hpp/fcl/fwd.hh>
@@ -183,48 +185,59 @@ void exposeShapes ()
 
 void exposeCollisionGeometries ()
 {
-  enum_<OBJECT_TYPE>("OBJECT_TYPE")
-    .value ("OT_UNKNOWN", OT_UNKNOWN)
-    .value ("OT_BVH"    , OT_BVH)
-    .value ("OT_GEOM"   , OT_GEOM)
-    .value ("OT_OCTREE" , OT_OCTREE)
-    ;
-  enum_<NODE_TYPE>("NODE_TYPE")
-    .value ("BV_UNKNOWN", BV_UNKNOWN)
-    .value ("BV_AABB"  , BV_AABB)
-    .value ("BV_OBB"   , BV_OBB)
-    .value ("BV_RSS"   , BV_RSS)
-    .value ("BV_kIOS"  , BV_kIOS)
-    .value ("BV_OBBRSS", BV_OBBRSS)
-    .value ("BV_KDOP16", BV_KDOP16)
-    .value ("BV_KDOP18", BV_KDOP18)
-    .value ("BV_KDOP24", BV_KDOP24)
-    .value ("GEOM_BOX"      , GEOM_BOX)
-    .value ("GEOM_SPHERE"   , GEOM_SPHERE)
-    .value ("GEOM_CAPSULE"  , GEOM_CAPSULE)
-    .value ("GEOM_CONE"     , GEOM_CONE)
-    .value ("GEOM_CYLINDER" , GEOM_CYLINDER)
-    .value ("GEOM_CONVEX"   , GEOM_CONVEX)
-    .value ("GEOM_PLANE"    , GEOM_PLANE)
-    .value ("GEOM_HALFSPACE", GEOM_HALFSPACE)
-    .value ("GEOM_TRIANGLE" , GEOM_TRIANGLE)
-    .value ("GEOM_OCTREE"   , GEOM_OCTREE)
-    ;
+  
+  if(!eigenpy::register_symbolic_link_to_registered_type<OBJECT_TYPE>())
+  {
+    enum_<OBJECT_TYPE>("OBJECT_TYPE")
+      .value ("OT_UNKNOWN", OT_UNKNOWN)
+      .value ("OT_BVH"    , OT_BVH)
+      .value ("OT_GEOM"   , OT_GEOM)
+      .value ("OT_OCTREE" , OT_OCTREE)
+      ;
+  }
+  
+  if(!eigenpy::register_symbolic_link_to_registered_type<NODE_TYPE>())
+  {
+    enum_<NODE_TYPE>("NODE_TYPE")
+      .value ("BV_UNKNOWN", BV_UNKNOWN)
+      .value ("BV_AABB"  , BV_AABB)
+      .value ("BV_OBB"   , BV_OBB)
+      .value ("BV_RSS"   , BV_RSS)
+      .value ("BV_kIOS"  , BV_kIOS)
+      .value ("BV_OBBRSS", BV_OBBRSS)
+      .value ("BV_KDOP16", BV_KDOP16)
+      .value ("BV_KDOP18", BV_KDOP18)
+      .value ("BV_KDOP24", BV_KDOP24)
+      .value ("GEOM_BOX"      , GEOM_BOX)
+      .value ("GEOM_SPHERE"   , GEOM_SPHERE)
+      .value ("GEOM_CAPSULE"  , GEOM_CAPSULE)
+      .value ("GEOM_CONE"     , GEOM_CONE)
+      .value ("GEOM_CYLINDER" , GEOM_CYLINDER)
+      .value ("GEOM_CONVEX"   , GEOM_CONVEX)
+      .value ("GEOM_PLANE"    , GEOM_PLANE)
+      .value ("GEOM_HALFSPACE", GEOM_HALFSPACE)
+      .value ("GEOM_TRIANGLE" , GEOM_TRIANGLE)
+      .value ("GEOM_OCTREE"   , GEOM_OCTREE)
+      ;
+  }
 
-  class_ <CollisionGeometry, CollisionGeometryPtr_t, noncopyable>
-    ("CollisionGeometry", no_init)
-    .def ("getObjectType", &CollisionGeometry::getObjectType)
-    .def ("getNodeType", &CollisionGeometry::getNodeType)
+  if(!eigenpy::register_symbolic_link_to_registered_type<CollisionGeometry>())
+  {
+    class_ <CollisionGeometry, CollisionGeometryPtr_t, noncopyable>
+      ("CollisionGeometry", no_init)
+      .def ("getObjectType", &CollisionGeometry::getObjectType)
+      .def ("getNodeType", &CollisionGeometry::getNodeType)
 
-    .def ("computeLocalAABB", &CollisionGeometry::computeLocalAABB)
+      .def ("computeLocalAABB", &CollisionGeometry::computeLocalAABB)
 
-    .def ("computeCOM", &CollisionGeometry::computeCOM)
-    .def ("computeMomentofInertia", &CollisionGeometry::computeMomentofInertia)
-    .def ("computeVolume", &CollisionGeometry::computeVolume)
-    .def ("computeMomentofInertiaRelatedToCOM", &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
+      .def ("computeCOM", &CollisionGeometry::computeCOM)
+      .def ("computeMomentofInertia", &CollisionGeometry::computeMomentofInertia)
+      .def ("computeVolume", &CollisionGeometry::computeVolume)
+      .def ("computeMomentofInertiaRelatedToCOM", &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
 
-    .def_readwrite("aabb_radius",&CollisionGeometry::aabb_radius,"AABB radius")
-    ;
+      .def_readwrite("aabb_radius",&CollisionGeometry::aabb_radius,"AABB radius")
+      ;
+  }
 
   exposeShapes();
 
diff --git a/python/collision.cc b/python/collision.cc
index 47be7f5eae7b7f463195fa3bedd509406d63ea89..728d0735a533df30dadb56a7907a100257ce2fca 100644
--- a/python/collision.cc
+++ b/python/collision.cc
@@ -1,7 +1,7 @@
 //
 // Software License Agreement (BSD License)
 //
-//  Copyright (c) 2019 CNRS-LAAS
+//  Copyright (c) 2019 CNRS-LAAS INRIA
 //  Author: Joseph Mirabel
 //  All rights reserved.
 //
@@ -35,6 +35,8 @@
 #include <boost/python.hpp>
 #include <boost/python/suite/indexing/vector_indexing_suite.hpp>
 
+#include <eigenpy/registration.hpp>
+
 #include "fcl.hh"
 
 #include <hpp/fcl/fwd.hh>
@@ -43,58 +45,75 @@
 using namespace boost::python;
 
 using namespace hpp::fcl;
-using boost::shared_ptr;
-using boost::noncopyable;
 
 void exposeCollisionAPI ()
 {
-  enum_ <CollisionRequestFlag> ("CollisionRequestFlag")
-    .value ("CONTACT", CONTACT)
-    .value ("DISTANCE_LOWER_BOUND", DISTANCE_LOWER_BOUND)
-    .value ("NO_REQUEST", NO_REQUEST)
-    ;
-
-  class_ <CollisionRequest> ("CollisionRequest", init<>())
-    .def (init<CollisionRequestFlag, size_t>())
+  if(!eigenpy::register_symbolic_link_to_registered_type<CollisionRequestFlag>())
+  {
+    enum_ <CollisionRequestFlag> ("CollisionRequestFlag")
+      .value ("CONTACT", CONTACT)
+      .value ("DISTANCE_LOWER_BOUND", DISTANCE_LOWER_BOUND)
+      .value ("NO_REQUEST", NO_REQUEST)
+      ;
+  }
 
-    .def_readwrite ("num_max_contacts"           , &CollisionRequest::num_max_contacts)
-    .def_readwrite ("enable_contact"             , &CollisionRequest::enable_contact)
-    .def_readwrite ("enable_distance_lower_bound", &CollisionRequest::enable_distance_lower_bound)
-    .def_readwrite ("enable_cached_gjk_guess"    , &CollisionRequest::enable_cached_gjk_guess)
-    .def_readwrite ("cached_gjk_guess"           , &CollisionRequest::cached_gjk_guess)
-    .def_readwrite ("security_margin"            , &CollisionRequest::security_margin)
-    .def_readwrite ("break_distance"             , &CollisionRequest::break_distance)
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type<CollisionRequest>())
+  {
+    class_ <CollisionRequest> ("CollisionRequest", init<>())
+      .def (init<CollisionRequestFlag, size_t>())
+    
+      .def_readwrite ("num_max_contacts"           , &CollisionRequest::num_max_contacts)
+      .def_readwrite ("enable_contact"             , &CollisionRequest::enable_contact)
+      .def_readwrite ("enable_distance_lower_bound", &CollisionRequest::enable_distance_lower_bound)
+      .def_readwrite ("enable_cached_gjk_guess"    , &CollisionRequest::enable_cached_gjk_guess)
+      .def_readwrite ("cached_gjk_guess"           , &CollisionRequest::cached_gjk_guess)
+      .def_readwrite ("security_margin"            , &CollisionRequest::security_margin)
+      .def_readwrite ("break_distance"             , &CollisionRequest::break_distance)
+      ;
+  }
 
-  class_ <Contact> ("Contact", init<>())
-    //.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int>())
-    //.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int, Vec3f, Vec3f, FCL_REAL>())
-    .def_readonly ("o1", &Contact::o1)
-    .def_readonly ("o2", &Contact::o2)
-    .def_readwrite ("b1", &Contact::b1)
-    .def_readwrite ("b2", &Contact::b2)
-    .def_readwrite ("normal", &Contact::normal)
-    .def_readwrite ("pos", &Contact::pos)
-    .def_readwrite ("penetration_depth", &Contact::penetration_depth)
-    .def (self == self)
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type<Contact>())
+  {
+    class_ <Contact> ("Contact", init<>())
+      //.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int>())
+      //.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int, Vec3f, Vec3f, FCL_REAL>())
+      .def_readonly ("o1", &Contact::o1)
+      .def_readonly ("o2", &Contact::o2)
+      .def_readwrite ("b1", &Contact::b1)
+      .def_readwrite ("b2", &Contact::b2)
+      .def_readwrite ("normal", &Contact::normal)
+      .def_readwrite ("pos", &Contact::pos)
+      .def_readwrite ("penetration_depth", &Contact::penetration_depth)
+      .def (self == self)
+      .def (self != self)
+      ;
+  }
 
-  class_< std::vector<Contact> >("StdVec_Contact")
-    .def(vector_indexing_suite< std::vector<Contact> >())
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type< std::vector<Contact> >())
+  {
+    class_< std::vector<Contact> >("StdVec_Contact")
+      .def(vector_indexing_suite< std::vector<Contact> >())
+      ;
+  }
 
-  class_ <CollisionResult> ("CollisionResult", init<>())
-    .def ("isCollision", &CollisionResult::isCollision)
-    .def ("numContacts", &CollisionResult::numContacts)
-    .def ("getContact" , &CollisionResult::getContact , return_value_policy<copy_const_reference>())
-    .def ("getContacts", &CollisionResult::getContacts, return_internal_reference<>())
-    .def ("addContact" , &CollisionResult::addContact )
-    .def ("clear", &CollisionResult::clear)
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type< std::vector<CollisionResult> >())
+  {
+    class_ <CollisionResult> ("CollisionResult", init<>())
+      .def ("isCollision", &CollisionResult::isCollision)
+      .def ("numContacts", &CollisionResult::numContacts)
+      .def ("getContact" , &CollisionResult::getContact , return_value_policy<copy_const_reference>())
+      .def ("getContacts", &CollisionResult::getContacts, return_internal_reference<>())
+      .def ("addContact" , &CollisionResult::addContact )
+      .def ("clear", &CollisionResult::clear)
+      ;
+  }
 
-  class_< std::vector<CollisionResult> >("CollisionResult")
-    .def(vector_indexing_suite< std::vector<CollisionResult> >())
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type< std::vector<CollisionResult> >())
+  {
+    class_< std::vector<CollisionResult> >("CollisionResult")
+      .def(vector_indexing_suite< std::vector<CollisionResult> >())
+      ;
+  }
 
   def ("collide", static_cast< std::size_t (*)(const CollisionObject*, const CollisionObject*,
         const CollisionRequest&, CollisionResult&) > (&collide));
diff --git a/python/distance.cc b/python/distance.cc
index d7ca2e8f096798c3ada63f15e8745af95a678ec9..2ecefa77973ab4e26a0e55fd436f0b5059f920e0 100644
--- a/python/distance.cc
+++ b/python/distance.cc
@@ -1,7 +1,7 @@
 //
 // Software License Agreement (BSD License)
 //
-//  Copyright (c) 2019 CNRS-LAAS
+//  Copyright (c) 2019 CNRS-LAAS INRIA
 //  Author: Joseph Mirabel
 //  All rights reserved.
 //
@@ -35,6 +35,8 @@
 #include <boost/python.hpp>
 #include <boost/python/suite/indexing/vector_indexing_suite.hpp>
 
+#include <eigenpy/registration.hpp>
+
 #include "fcl.hh"
 
 #include <hpp/fcl/fwd.hh>
@@ -43,8 +45,6 @@
 using namespace boost::python;
 
 using namespace hpp::fcl;
-using boost::shared_ptr;
-using boost::noncopyable;
 
 struct DistanceRequestWrapper
 {
@@ -54,29 +54,38 @@ struct DistanceRequestWrapper
 
 void exposeDistanceAPI ()
 {
-  class_ <DistanceRequest> ("DistanceRequest", init<optional<bool,FCL_REAL,FCL_REAL> >())
-    .def_readwrite ("enable_nearest_points", &DistanceRequest::enable_nearest_points)
-    .def_readwrite ("rel_err"              , &DistanceRequest::rel_err)
-    .def_readwrite ("abs_err"              , &DistanceRequest::abs_err)
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type<DistanceRequest>())
+  {
+    class_ <DistanceRequest> ("DistanceRequest", init<optional<bool,FCL_REAL,FCL_REAL> >())
+      .def_readwrite ("enable_nearest_points", &DistanceRequest::enable_nearest_points)
+      .def_readwrite ("rel_err"              , &DistanceRequest::rel_err)
+      .def_readwrite ("abs_err"              , &DistanceRequest::abs_err)
+      ;
+  }
 
-  class_ <DistanceResult> ("DistanceResult", init<>())
-    .def_readwrite ("min_distance", &DistanceResult::min_distance)
-    .def_readwrite ("normal", &DistanceResult::normal)
-    //.def_readwrite ("nearest_points", &DistanceResult::nearest_points)
-    .def("getNearestPoint1",&DistanceRequestWrapper::getNearestPoint1)
-    .def("getNearestPoint2",&DistanceRequestWrapper::getNearestPoint2)
-    .def_readonly ("o1", &DistanceResult::o1)
-    .def_readonly ("o2", &DistanceResult::o2)
-    .def_readwrite ("b1", &DistanceResult::b1)
-    .def_readwrite ("b2", &DistanceResult::b2)
+  if(!eigenpy::register_symbolic_link_to_registered_type<DistanceResult>())
+  {
+    class_ <DistanceResult> ("DistanceResult", init<>())
+      .def_readwrite ("min_distance", &DistanceResult::min_distance)
+      .def_readwrite ("normal", &DistanceResult::normal)
+      //.def_readwrite ("nearest_points", &DistanceResult::nearest_points)
+      .def("getNearestPoint1",&DistanceRequestWrapper::getNearestPoint1)
+      .def("getNearestPoint2",&DistanceRequestWrapper::getNearestPoint2)
+      .def_readonly ("o1", &DistanceResult::o1)
+      .def_readonly ("o2", &DistanceResult::o2)
+      .def_readwrite ("b1", &DistanceResult::b1)
+      .def_readwrite ("b2", &DistanceResult::b2)
 
-    .def ("clear", &DistanceResult::clear)
-    ;
+      .def ("clear", &DistanceResult::clear)
+      ;
+  }
 
-  class_< std::vector<DistanceResult> >("StdVec_DistanceResult")
-    .def(vector_indexing_suite< std::vector<DistanceResult> >())
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type< std::vector<DistanceResult> >())
+  {
+    class_< std::vector<DistanceResult> >("StdVec_DistanceResult")
+      .def(vector_indexing_suite< std::vector<DistanceResult> >())
+      ;
+  }
 
   def ("distance", static_cast< FCL_REAL (*)(const CollisionObject*, const CollisionObject*,
         const DistanceRequest&, DistanceResult&) > (&distance));
diff --git a/python/fcl.cc b/python/fcl.cc
index 0aa4b104fb09dd6ff8a033237d409bd230483789..2396bec52f79f4c4d2d6af96bcaa725c46ce2d6a 100644
--- a/python/fcl.cc
+++ b/python/fcl.cc
@@ -1,7 +1,7 @@
 //
 // Software License Agreement (BSD License)
 //
-//  Copyright (c) 2019 CNRS-LAAS
+//  Copyright (c) 2019 CNRS-LAAS INRIA
 //  Author: Joseph Mirabel
 //  All rights reserved.
 //
@@ -34,6 +34,8 @@
 
 #include <boost/python.hpp>
 
+#include <eigenpy/registration.hpp>
+
 #include "fcl.hh"
 
 #include <hpp/fcl/fwd.hh>
@@ -47,17 +49,21 @@
 using namespace boost::python;
 
 using namespace hpp::fcl;
-using boost::shared_ptr;
-using boost::noncopyable;
 
 void exposeMeshLoader ()
 {
-  class_ <MeshLoader> ("MeshLoader", init< optional< NODE_TYPE> >())
-    .def ("load", static_cast <BVHModelPtr_t (MeshLoader::*) (const std::string&, const Vec3f&)> (&MeshLoader::load))
-    ;
+  if(!eigenpy::register_symbolic_link_to_registered_type<MeshLoader>())
+  {
+    class_ <MeshLoader> ("MeshLoader", init< optional< NODE_TYPE> >())
+      .def ("load", static_cast <BVHModelPtr_t (MeshLoader::*) (const std::string&, const Vec3f&)> (&MeshLoader::load))
+      ;
+  }
 
-  class_ <CachedMeshLoader, bases<MeshLoader> > ("CachedMeshLoader", init< optional< NODE_TYPE> >())
+  if(!eigenpy::register_symbolic_link_to_registered_type<CachedMeshLoader>())
+  {
+    class_ <CachedMeshLoader, bases<MeshLoader> > ("CachedMeshLoader", init< optional< NODE_TYPE> >())
     ;
+  }
 }
 
 BOOST_PYTHON_MODULE(hppfcl)
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 4a5ac568ef71ad2693aee5b20f254e7788e20a77..9e4e1dc2a76000042985368d4cfa91d83842fd4c 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -82,11 +82,21 @@ set(${LIBRARY_NAME}_SOURCES
   mesh_loader/loader.cpp
   )
 
+SET(PROJECT_HEADERS_FULL_PATH)
+FOREACH(header ${${PROJECT_NAME}_HEADERS})
+  LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_SOURCE_DIR}/${header})
+ENDFOREACH()
+LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/hpp/fcl/config.hh)
 add_library(${LIBRARY_NAME}
   SHARED
+  ${PROJECT_HEADERS_FULL_PATH}
   ${${LIBRARY_NAME}_SOURCES}
   )
 
+# IDE sources and headers sorting
+ADD_SOURCE_GROUP(${LIBRARY_NAME}_SOURCES)
+ADD_HEADER_GROUP(PROJECT_HEADERS_FULL_PATH)
+
 TARGET_LINK_LIBRARIES(${LIBRARY_NAME} 
   PUBLIC 
   Boost::thread
@@ -102,7 +112,7 @@ target_include_directories(${LIBRARY_NAME}
 target_include_directories(${LIBRARY_NAME} 
   PUBLIC
   $<INSTALL_INTERFACE:${CMAKE_INSTALL_INCLUDEDIR}>
-)
+  )
 
 PKG_CONFIG_USE_DEPENDENCY(${LIBRARY_NAME} assimp)
 if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150")
diff --git a/src/distance_box_halfspace.cpp b/src/distance_box_halfspace.cpp
index 191cf09bcb86f2c04b7ae9aeb8b78ee11cae41b9..0b42a4b16532cae7914a3396340e9e31a4fe674a 100644
--- a/src/distance_box_halfspace.cpp
+++ b/src/distance_box_halfspace.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Box, Halfspace>
diff --git a/src/distance_box_plane.cpp b/src/distance_box_plane.cpp
index d63879225374473452c6aa0387b9cd323508c2c2..841b17b65b317a37da1c7a2000624887d150db53 100644
--- a/src/distance_box_plane.cpp
+++ b/src/distance_box_plane.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Box, Plane>
diff --git a/src/distance_box_sphere.cpp b/src/distance_box_sphere.cpp
index f35030e308a3342788832a944ac6f0877640423c..a98f9fe7e602d9d0d3ef9f04a99efd5ee78f0646 100644
--- a/src/distance_box_sphere.cpp
+++ b/src/distance_box_sphere.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Box, Sphere>
diff --git a/src/distance_capsule_halfspace.cpp b/src/distance_capsule_halfspace.cpp
index f33fc5175999bacab4c1223243074d8356b6f278..1175b5aebae7781ceb88d415280000e666cd4fb9 100644
--- a/src/distance_capsule_halfspace.cpp
+++ b/src/distance_capsule_halfspace.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Capsule, Halfspace>
diff --git a/src/distance_capsule_plane.cpp b/src/distance_capsule_plane.cpp
index beb862d065661df9a52cd813083ad2893230c917..a1ad00b7edbaaa89efc33dd1a9f262f63a0183a2 100644
--- a/src/distance_capsule_plane.cpp
+++ b/src/distance_capsule_plane.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Capsule, Plane>
diff --git a/src/distance_cone_halfspace.cpp b/src/distance_cone_halfspace.cpp
index 0191f6530d5e6c4b1ee2014c223bc92c721d2b62..580a88c9e4d0bb91c58515284f98fe849b1c2ebb 100644
--- a/src/distance_cone_halfspace.cpp
+++ b/src/distance_cone_halfspace.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Cone, Halfspace>
diff --git a/src/distance_cone_plane.cpp b/src/distance_cone_plane.cpp
index bc66f953b9ae9e4db6fa17d2e70a3c74ef8e31a1..f12eeab546c183e59042c9f4c314bf364b1940c5 100644
--- a/src/distance_cone_plane.cpp
+++ b/src/distance_cone_plane.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Cone, Plane>
diff --git a/src/distance_cylinder_halfspace.cpp b/src/distance_cylinder_halfspace.cpp
index dd469a6c4378999c390795d9b5a59d18e3d8dd39..c35041e0134c66af76786cd8dc339a9de5f883eb 100644
--- a/src/distance_cylinder_halfspace.cpp
+++ b/src/distance_cylinder_halfspace.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Cylinder, Halfspace>
diff --git a/src/distance_cylinder_plane.cpp b/src/distance_cylinder_plane.cpp
index e8be52cb7c2e938b92bec2ed900cd919f8c65add..8e335ec1fc51ad9fd424dd4344a3a01f133ce34a 100644
--- a/src/distance_cylinder_plane.cpp
+++ b/src/distance_cylinder_plane.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Cylinder, Plane>
diff --git a/src/distance_func_matrix.h b/src/distance_func_matrix.h
index 3a142614f523f3a9e35b285c248a46852edebd6f..6210118015c919c3e4bc041fd2cb2465cfcaf6ea 100644
--- a/src/distance_func_matrix.h
+++ b/src/distance_func_matrix.h
@@ -65,4 +65,5 @@ namespace fcl
 
 /// @endcond
 
-#endif
\ No newline at end of file
+#endif
+
diff --git a/src/distance_sphere_cylinder.cpp b/src/distance_sphere_cylinder.cpp
index 993933d98c11437394116540f907edf0ba0c8300..c53e472772493ee4fc363f921836820a3deb83e1 100644
--- a/src/distance_sphere_cylinder.cpp
+++ b/src/distance_sphere_cylinder.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Sphere, Cylinder>
diff --git a/src/distance_sphere_halfspace.cpp b/src/distance_sphere_halfspace.cpp
index 6c7b9b7435a01e4785b401640f1f35064103295f..8e069eb10dbcd9267ad800068dcc418ceed11d1e 100644
--- a/src/distance_sphere_halfspace.cpp
+++ b/src/distance_sphere_halfspace.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Sphere, Halfspace>
diff --git a/src/distance_sphere_plane.cpp b/src/distance_sphere_plane.cpp
index 28754534852fc053ed52621d8cedae1298ac8d22..c1ce63258706de338332e78df116479fcf38c774 100644
--- a/src/distance_sphere_plane.cpp
+++ b/src/distance_sphere_plane.cpp
@@ -46,7 +46,7 @@
 namespace hpp
 {
 namespace fcl {
-    class GJKSolver;
+  struct GJKSolver;
 
   template <>
   FCL_REAL ShapeShapeDistance <Sphere, Plane>
diff --git a/src/mesh_loader/assimp.cpp b/src/mesh_loader/assimp.cpp
index 2645a4be2e07729b069eabe4bf8d00647a09e352..a160555a0a42cecb3853e2ea8264eb71397b4f60 100644
--- a/src/mesh_loader/assimp.cpp
+++ b/src/mesh_loader/assimp.cpp
@@ -32,6 +32,9 @@
  *  POSSIBILITY OF SUCH DAMAGE.
  */
 
+#if __cplusplus < 201103L
+  #define nullptr NULL
+#endif
 #include <hpp/fcl/mesh_loader/assimp.h>
 
 // Assimp >= 5.0 is forcing the use of C++11 keywords. A fix has been submitted https://github.com/assimp/assimp/pull/2758.
diff --git a/src/traits_traversal.h b/src/traits_traversal.h
index c296ac8fd1068d251f17d5c905d94497c8e2907c..d52005abd39588a4e5f0be0b0d352d58133cadc1 100644
--- a/src/traits_traversal.h
+++ b/src/traits_traversal.h
@@ -102,4 +102,5 @@ struct TraversalTraitsDistance <BVHModel<T_BVH>, OcTree>
 
 }
 
-} //hpp
\ No newline at end of file
+} //hpp
+
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 982b06c4ffccd5bb79782d85408de339e3d8aec7..86201e6d73fbe99130fd22c7f13e65dd4075306b 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -11,6 +11,7 @@ macro(add_fcl_test test_name)
     )
   PKG_CONFIG_USE_DEPENDENCY(${test_name} assimp)
   add_test(${test_name} ${EXECUTABLE_OUTPUT_PATH}/${test_name})
+  target_compile_options(${test_name} PRIVATE "-Wno-c99-extensions")
 endmacro(add_fcl_test)
 
 include_directories(${CMAKE_CURRENT_BINARY_DIR})
diff --git a/test/benchmark.cpp b/test/benchmark.cpp
index 2b120ad0963bc32ac7d34ff2e8711b2b13767062..2c97c37051fc2c96606e26920bc8cb0146ae05e3 100644
--- a/test/benchmark.cpp
+++ b/test/benchmark.cpp
@@ -160,7 +160,7 @@ double run<OBB> (const std::vector<Transform3f>& tf,
                  const BVHModel<OBB> (&models)[2][3], int split_method,
                  const char* prefix)
 {
-  double col  = collide <OBB, typename traits<OBB>::CollisionTraversalNode>
+  double col  = collide <OBB,traits<OBB>::CollisionTraversalNode>
     (tf, models[0][split_method], models[1][split_method], verbose);
   double dist = 0;