From dab9e07d473108707c45d8eefde7d7064a6d7098 Mon Sep 17 00:00:00 2001
From: Valenza Florian <fvalenza@laas.fr>
Date: Fri, 29 Jul 2016 15:26:37 +0200
Subject: [PATCH] [C++] Moved fcl related structures to multibody/fcl.hpp +
 rework somes inclusion directives

---
 CMakeLists.txt                |   1 +
 src/algorithm/geometry.hxx    |   2 +-
 src/multibody/fcl.hpp         | 237 ++++++++++++++++++++++++++++++++++
 src/multibody/geometry.hpp    | 217 +------------------------------
 src/multibody/geometry.hxx    |  33 ++---
 src/parsers/urdf.hpp          |   3 -
 src/parsers/urdf/geometry.cpp |   1 +
 src/python/geometry-data.hpp  |   5 +-
 src/python/geometry-model.hpp |  10 +-
 9 files changed, 260 insertions(+), 249 deletions(-)
 create mode 100644 src/multibody/fcl.hpp

diff --git a/CMakeLists.txt b/CMakeLists.txt
index d1f102191..7b3a2d855 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -256,6 +256,7 @@ IF(HPP_FCL_FOUND)
     spatial/fcl-pinocchio-conversions.hpp
     )
   LIST(APPEND ${PROJECT_NAME}_MULTIBODY_HEADERS
+    multibody/fcl.hpp
     multibody/geometry.hpp
     multibody/geometry.hxx
     )
diff --git a/src/algorithm/geometry.hxx b/src/algorithm/geometry.hxx
index 6b3db72e2..75f85cc0b 100644
--- a/src/algorithm/geometry.hxx
+++ b/src/algorithm/geometry.hxx
@@ -40,7 +40,7 @@ namespace se3
                                        GeometryData & data_geom
                                        )
   {
-    for (GeometryData::GeomIndex i=0; i < (GeometryData::GeomIndex) data_geom.model_geom.ngeoms; ++i)
+    for (GeomIndex i=0; i < (GeomIndex) data_geom.model_geom.ngeoms; ++i)
     {
       const Model::JointIndex & parent = model_geom.geometryObjects[i].parent;
       if (parent>0) data_geom.oMg[i] =  (data.oMi[parent] * model_geom.geometryObjects[i].placement);
diff --git a/src/multibody/fcl.hpp b/src/multibody/fcl.hpp
new file mode 100644
index 000000000..5bfdef125
--- /dev/null
+++ b/src/multibody/fcl.hpp
@@ -0,0 +1,237 @@
+//
+// 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_hpp__
+#define __se3_fcl_hpp__
+
+#include "pinocchio/multibody/fwd.hpp"
+#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
+
+#include <hpp/fcl/collision_object.h>
+#include <hpp/fcl/collision.h>
+#include <hpp/fcl/distance.h>
+#include <hpp/fcl/shape/geometric_shapes.h>
+
+#include <iostream>
+#include <map>
+#include <list>
+#include <utility>
+#include <assert.h>
+
+#include <boost/foreach.hpp>
+
+namespace se3
+{
+  struct CollisionPair: public std::pair<GeomIndex, GeomIndex>
+  {
+
+    typedef std::pair<GeomIndex, GeomIndex> Base;
+   
+    ///
+    /// \brief Default constructor of a collision pair from two collision object indexes.
+    ///        The indexes must be ordered such that co1 < co2. If not, the constructor reverts the indexes.
+    ///
+    /// \param[in] co1 Index of the first collision object
+    /// \param[in] co2 Index of the second collision object
+    ///
+    CollisionPair(const GeomIndex co1, const GeomIndex co2) : Base(co1,co2)
+    {
+      assert(co1 != co2 && "The index of collision objects must not be equal.");
+    }
+
+    bool operator== (const CollisionPair& rhs) const
+    {
+      return (first == rhs.first && second == rhs.second)
+        || (first == rhs.second && second == rhs.first);
+    }
+    
+    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;
+    }
+  }; // struct CollisionPair
+  typedef std::vector<CollisionPair> CollisionPairsVector_t;
+  
+  /**
+   * @brief      Result of distance computation between two CollisionObjects
+   */
+  struct DistanceResult
+  {
+
+    DistanceResult() : fcl_distance_result(), object1(0), object2(0) {}
+    DistanceResult(fcl::DistanceResult dist_fcl, const GeomIndex co1, const GeomIndex co2)
+    : fcl_distance_result(dist_fcl), object1(co1), object2(co2)
+    {}
+
+
+    ///
+    /// @brief Return the minimal distance between two geometry objects
+    ///
+    double distance () const { return fcl_distance_result.min_distance; }
+
+    ///
+    /// \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]); }
+    
+    ///
+    /// \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]); }
+    
+    bool operator == (const DistanceResult & other) const
+    {
+      return (distance() == other.distance()
+        && closestPointInner() == other.closestPointInner()
+        && closestPointOuter() == other.closestPointOuter()
+        && object1 == other.object1
+        && object2 == other.object2);
+    }
+    
+    /// \brief The FCL result of the distance computation
+    fcl::DistanceResult fcl_distance_result;
+    
+    /// \brief Index of the first colision object
+    GeomIndex object1;
+
+    /// \brief Index of the second colision object
+    GeomIndex object2;
+    
+  }; // struct DistanceResult 
+  
+
+  /**
+   * @brief      Result of collision computation between two CollisionObjects
+   */
+  struct CollisionResult
+  {
+
+    /**
+     * @brief      Default constrcutor of a CollisionResult
+     *
+     * @param[in]  coll_fcl  The FCL collision result
+     * @param[in]  co1       Index of the first geometry object involved in the computation
+     * @param[in]  co2       Index of the second geometry object involved in the computation
+     */
+    CollisionResult(fcl::CollisionResult coll_fcl, const GeomIndex co1, const GeomIndex co2)
+    : fcl_collision_result(coll_fcl), object1(co1), object2(co2)
+    {}
+    CollisionResult() : fcl_collision_result(), object1(0), object2(0) {}
+
+    bool operator == (const CollisionResult & other) const
+    {
+      return (fcl_collision_result == other.fcl_collision_result
+              && object1 == other.object1
+              && object2 == other.object2);
+    }
+
+    /// \brief The FCL result of the collision computation
+    fcl::CollisionResult fcl_collision_result;
+
+    /// \brief Index of the first collision object
+    GeomIndex object1;
+
+    /// \brief Index of the second collision object
+    GeomIndex object2;
+
+  }; // 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_;
+}
+enum GeometryType
+{
+  VISUAL,
+  COLLISION,
+  NONE
+};
+
+struct GeometryObject
+{
+
+  /// \brief Name of the geometry object
+  std::string name;
+
+  /// \brief Index of the parent joint
+  JointIndex parent;
+
+  /// \brief The actual cloud of points representing the collision mesh of the object
+  boost::shared_ptr<fcl::CollisionGeometry> collision_geometry;
+
+  /// \brief Position of geometry object in parent joint's frame
+  SE3 placement;
+
+  /// \brief Absolute path to the mesh file
+  std::string mesh_path;
+
+
+  GeometryObject(const std::string & name, const JointIndex parent, const boost::shared_ptr<fcl::CollisionGeometry> & collision,
+                 const SE3 & placement, const std::string & mesh_path)
+                : name(name)
+                , parent(parent)
+                , collision_geometry(collision)
+                , placement(placement)
+                , mesh_path(mesh_path)
+  {}
+
+  GeometryObject & operator=(const GeometryObject & other)
+  {
+    name = other.name;
+    parent = other.parent;
+    collision_geometry = other.collision_geometry;
+    placement = other.placement;
+    mesh_path = other.mesh_path;
+    return *this;
+  }
+
+};
+  
+  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
+
+/* --- Details -------------------------------------------------------------- */
+/* --- Details -------------------------------------------------------------- */
+/* --- Details -------------------------------------------------------------- */
+
+
+#endif // ifndef __se3_fcl_hpp__
diff --git a/src/multibody/geometry.hpp b/src/multibody/geometry.hpp
index fc65a0773..a5b4c1e93 100644
--- a/src/multibody/geometry.hpp
+++ b/src/multibody/geometry.hpp
@@ -19,19 +19,11 @@
 #define __se3_geom_hpp__
 
 
-#include "pinocchio/spatial/fwd.hpp"
-#include "pinocchio/spatial/se3.hpp"
-#include "pinocchio/spatial/force.hpp"
-#include "pinocchio/spatial/motion.hpp"
-#include "pinocchio/spatial/inertia.hpp"
-#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
+#include "pinocchio/multibody/fcl.hpp"
 #include "pinocchio/multibody/model.hpp"
-#include "pinocchio/multibody/joint/joint-variant.hpp"
+
 #include <iostream>
 
-#include <hpp/fcl/collision_object.h>
-#include <hpp/fcl/collision.h>
-#include <hpp/fcl/distance.h>
 #include <boost/foreach.hpp>
 #include <map>
 #include <list>
@@ -41,210 +33,9 @@
 
 namespace se3
 {
-  struct CollisionPair: public std::pair<Model::GeomIndex, Model::GeomIndex>
-  {
-    typedef Model::Index Index;
-    typedef Model::GeomIndex GeomIndex;
-    typedef std::pair<Model::GeomIndex, Model::GeomIndex> Base;
-   
-    ///
-    /// \brief Default constructor of a collision pair from two collision object indexes.
-    ///        The indexes must be ordered such that co1 < co2. If not, the constructor reverts the indexes.
-    ///
-    /// \param[in] co1 Index of the first collision object
-    /// \param[in] co2 Index of the second collision object
-    ///
-    CollisionPair(const GeomIndex co1, const GeomIndex co2) : Base(co1,co2)
-    {
-      assert(co1 != co2 && "The index of collision objects must not be equal.");
-    }
-
-    bool operator== (const CollisionPair& rhs) const
-    {
-      return (first == rhs.first && second == rhs.second)
-        || (first == rhs.second && second == rhs.first);
-    }
-    
-    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;
-    }
-  }; // struct CollisionPair
-  typedef std::vector<CollisionPair> CollisionPairsVector_t;
-  
-  /**
-   * @brief      Result of distance computation between two CollisionObjects
-   */
-  struct DistanceResult
-  {
-    typedef Model::Index Index;
-    typedef Model::GeomIndex GeomIndex;
-
-    DistanceResult() : fcl_distance_result(), object1(0), object2(0) {}
-    DistanceResult(fcl::DistanceResult dist_fcl, const GeomIndex co1, const GeomIndex co2)
-    : fcl_distance_result(dist_fcl), object1(co1), object2(co2)
-    {}
-
-
-    ///
-    /// @brief Return the minimal distance between two geometry objects
-    ///
-    double distance () const { return fcl_distance_result.min_distance; }
-
-    ///
-    /// \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]); }
-    
-    ///
-    /// \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]); }
-    
-    bool operator == (const DistanceResult & other) const
-    {
-      return (distance() == other.distance()
-        && closestPointInner() == other.closestPointInner()
-        && closestPointOuter() == other.closestPointOuter()
-        && object1 == other.object1
-        && object2 == other.object2);
-    }
-    
-    /// \brief The FCL result of the distance computation
-    fcl::DistanceResult fcl_distance_result;
-    
-    /// \brief Index of the first colision object
-    GeomIndex object1;
-
-    /// \brief Index of the second colision object
-    GeomIndex object2;
-    
-  }; // struct DistanceResult 
-  
-
-  /**
-   * @brief      Result of collision computation between two CollisionObjects
-   */
-  struct CollisionResult
-  {
-    typedef Model::Index Index;
-    typedef Model::GeomIndex GeomIndex;
-
-    /**
-     * @brief      Default constrcutor of a CollisionResult
-     *
-     * @param[in]  coll_fcl  The FCL collision result
-     * @param[in]  co1       Index of the first geometry object involved in the computation
-     * @param[in]  co2       Index of the second geometry object involved in the computation
-     */
-    CollisionResult(fcl::CollisionResult coll_fcl, const GeomIndex co1, const GeomIndex co2)
-    : fcl_collision_result(coll_fcl), object1(co1), object2(co2)
-    {}
-    CollisionResult() : fcl_collision_result(), object1(0), object2(0) {}
-
-    bool operator == (const CollisionResult & other) const
-    {
-      return (fcl_collision_result == other.fcl_collision_result
-              && object1 == other.object1
-              && object2 == other.object2);
-    }
-
-    /// \brief The FCL result of the collision computation
-    fcl::CollisionResult fcl_collision_result;
-
-    /// \brief Index of the first collision object
-    GeomIndex object1;
-
-    /// \brief Index of the second collision object
-    GeomIndex object2;
-
-  }; // 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_;
-}
-enum GeometryType
-{
-  VISUAL,
-  COLLISION,
-  NONE
-};
-
-struct GeometryObject
-{
-  typedef Model::Index Index;
-  typedef Model::JointIndex JointIndex;
-  typedef Model::GeomIndex GeomIndex;
-
-
-  /// \brief Name of the geometry object
-  std::string name;
-
-  /// \brief Index of the parent joint
-  JointIndex parent;
-
-  /// \brief The actual cloud of points representing the collision mesh of the object
-  boost::shared_ptr<fcl::CollisionGeometry> collision_geometry;
-
-  /// \brief Position of geometry object in parent joint's frame
-  SE3 placement;
-
-  /// \brief Absolute path to the mesh file
-  std::string mesh_path;
-
-
-  GeometryObject(const std::string & name, const JointIndex parent, const boost::shared_ptr<fcl::CollisionGeometry> & collision,
-                 const SE3 & placement, const std::string & mesh_path)
-                : name(name)
-                , parent(parent)
-                , collision_geometry(collision)
-                , placement(placement)
-                , mesh_path(mesh_path)
-  {}
-
-  GeometryObject & operator=(const GeometryObject & other)
-  {
-    name = other.name;
-    parent = other.parent;
-    collision_geometry = other.collision_geometry;
-    placement = other.placement;
-    mesh_path = other.mesh_path;
-    return *this;
-  }
-
-};
   
-  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;
-  }
-
   struct GeometryModel
   {
-    typedef Model::Index Index;
-    typedef Model::JointIndex JointIndex;
-    typedef Model::GeomIndex GeomIndex;
     
     typedef std::vector<GeomIndex> GeomIndexList;
 
@@ -394,9 +185,7 @@ struct GeometryObject
 
   struct GeometryData
   {
-    typedef Model::Index Index;
-    typedef Model::GeomIndex GeomIndex;
-    
+
     ///
     /// \brief A const reference to the model storing all the geometries.
     ///        See class GeometryModel.
diff --git a/src/multibody/geometry.hxx b/src/multibody/geometry.hxx
index fa6a4e276..5398b297e 100644
--- a/src/multibody/geometry.hxx
+++ b/src/multibody/geometry.hxx
@@ -19,19 +19,10 @@
 #define __se3_geometry_hxx__
 
 
-#include "pinocchio/spatial/fwd.hpp"
-#include "pinocchio/spatial/se3.hpp"
-#include "pinocchio/spatial/force.hpp"
-#include "pinocchio/spatial/motion.hpp"
-#include "pinocchio/spatial/inertia.hpp"
-#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
-#include "pinocchio/multibody/model.hpp"
-#include "pinocchio/multibody/joint/joint-variant.hpp"
+
 #include <iostream>
 
-#include <hpp/fcl/collision_object.h>
-#include <hpp/fcl/collision.h>
-#include <hpp/fcl/distance.h>
+
 #include <map>
 #include <list>
 #include <utility>
@@ -41,11 +32,11 @@
 namespace se3
 {
 
-  inline GeometryModel::GeomIndex GeometryModel::addGeometryObject(const JointIndex parent,
-                                                                   const boost::shared_ptr<fcl::CollisionGeometry> & co,
-                                                                   const SE3 & placement,
-                                                                   const std::string & geom_name,
-                                                                   const std::string & mesh_path) throw(std::invalid_argument)
+  inline GeomIndex GeometryModel::addGeometryObject(const JointIndex parent,
+                                                    const boost::shared_ptr<fcl::CollisionGeometry> & co,
+                                                    const SE3 & placement,
+                                                    const std::string & geom_name,
+                                                    const std::string & mesh_path) throw(std::invalid_argument)
   {
 
     Index idx = (Index) (ngeoms ++);
@@ -57,14 +48,14 @@ namespace se3
   }
 
 
-  inline GeometryModel::GeomIndex GeometryModel::getGeometryId(const std::string & name) const
+  inline GeomIndex GeometryModel::getGeometryId(const std::string & name) const
   {
 
     std::vector<GeometryObject>::const_iterator it = std::find_if(geometryObjects.begin(),
                                                                   geometryObjects.end(),
                                                                   boost::bind(&GeometryObject::name, _1) == name
                                                                   );
-    return GeometryModel::GeomIndex(it - geometryObjects.begin());
+    return GeomIndex(it - geometryObjects.begin());
   }
 
 
@@ -108,7 +99,7 @@ namespace se3
   {
     os << "Nb geometry objects = " << model_geom.ngeoms << std::endl;
     
-    for(GeometryModel::Index i=0;i<(GeometryModel::Index)(model_geom.ngeoms);++i)
+    for(Index i=0;i<(Index)(model_geom.ngeoms);++i)
     {
       os  << model_geom.geometryObjects[i] <<std::endl;
     }
@@ -120,7 +111,7 @@ namespace se3
   {
     os << "Nb collision pairs = " << data_geom.activeCollisionPairs.size() << std::endl;
     
-    for(GeometryData::Index i=0;i<(GeometryData::Index)(data_geom.activeCollisionPairs.size());++i)
+    for(Index i=0;i<(Index)(data_geom.activeCollisionPairs.size());++i)
     {
       os << "collision object in position " << data_geom.model_geom.collisionPairs[i] << std::endl;
     }
@@ -161,7 +152,7 @@ namespace se3
                       pair) != collisionPairs.end());
   }
   
-  inline GeometryModel::Index GeometryModel::findCollisionPair (const CollisionPair & pair) const
+  inline Index GeometryModel::findCollisionPair (const CollisionPair & pair) const
   {
     CollisionPairsVector_t::const_iterator it = std::find(collisionPairs.begin(),
                                                           collisionPairs.end(),
diff --git a/src/parsers/urdf.hpp b/src/parsers/urdf.hpp
index 45c3a9b48..9df51afcd 100644
--- a/src/parsers/urdf.hpp
+++ b/src/parsers/urdf.hpp
@@ -23,9 +23,6 @@
 #include "pinocchio/deprecated.hh"
 #ifdef WITH_HPP_FCL
   #include "pinocchio/multibody/geometry.hpp"
-  #include <hpp/fcl/collision_object.h>
-  #include <hpp/fcl/collision.h>
-  #include <hpp/fcl/shape/geometric_shapes.h>
 #endif
 
 #include <urdf_model/model.h>
diff --git a/src/parsers/urdf/geometry.cpp b/src/parsers/urdf/geometry.cpp
index 71a8f097f..aaf0c5249 100644
--- a/src/parsers/urdf/geometry.cpp
+++ b/src/parsers/urdf/geometry.cpp
@@ -15,6 +15,7 @@
 // Pinocchio If not, see
 // <http://www.gnu.org/licenses/>.
 
+
 #include "pinocchio/parsers/urdf.hpp"
 #include "pinocchio/parsers/urdf/utils.hpp"
 #include "pinocchio/parsers/utils.hpp"
diff --git a/src/python/geometry-data.hpp b/src/python/geometry-data.hpp
index 69b2cad47..d3f433ea0 100644
--- a/src/python/geometry-data.hpp
+++ b/src/python/geometry-data.hpp
@@ -40,8 +40,7 @@ namespace se3
     struct CollisionPairPythonVisitor
     : public boost::python::def_visitor<CollisionPairPythonVisitor>
     {
-      typedef CollisionPair::Index Index;
-      typedef CollisionPair::GeomIndex GeomIndex;
+
       static void expose()
       {
         bp::class_<CollisionPair> ("CollisionPair",
@@ -69,8 +68,6 @@ namespace se3
     struct GeometryDataPythonVisitor
       : public boost::python::def_visitor< GeometryDataPythonVisitor >
     {
-      typedef GeometryData::Index Index;
-      typedef GeometryData::GeomIndex GeomIndex;
       typedef eigenpy::UnalignedEquivalent<SE3>::type SE3_fx;
       
       /* --- Convert From C++ to Python ------------------------------------- */
diff --git a/src/python/geometry-model.hpp b/src/python/geometry-model.hpp
index 8f01432fc..3ba6a860e 100644
--- a/src/python/geometry-model.hpp
+++ b/src/python/geometry-model.hpp
@@ -40,9 +40,7 @@ namespace se3
       : public boost::python::def_visitor< GeometryModelPythonVisitor >
     {
     public:
-      typedef GeometryModel::Index Index;
-      typedef GeometryModel::JointIndex JointIndex;
-      typedef GeometryModel::GeomIndex GeomIndex;
+
       typedef eigenpy::UnalignedEquivalent<SE3>::type SE3_fx;
       
     public:
@@ -103,9 +101,9 @@ namespace se3
 	  ;
       }
 
-      static GeometryModel::Index ngeoms( GeometryModelHandler & m ) { return m->ngeoms; }
+      static Index ngeoms( GeometryModelHandler & m ) { return m->ngeoms; }
 
-      static Model::GeomIndex getGeometryId( const GeometryModelHandler & gmodelPtr, const std::string & name )
+      static GeomIndex getGeometryId( const GeometryModelHandler & gmodelPtr, const std::string & name )
       { return  gmodelPtr->getGeometryId(name); }
       static bool existGeometryName(const GeometryModelHandler & gmodelPtr, const std::string & name)
       { return gmodelPtr->existGeometryName(name);}
@@ -132,7 +130,7 @@ namespace se3
       static bool existCollisionPair (const GeometryModelHandler & m, const GeomIndex co1, const GeomIndex co2)
       { return m->existCollisionPair(CollisionPair(co1,co2)); }
 
-      static GeometryModel::Index findCollisionPair (const GeometryModelHandler & m, const GeomIndex co1, 
+      static Index findCollisionPair (const GeometryModelHandler & m, const GeomIndex co1, 
                                                      const GeomIndex co2)
       { return m->findCollisionPair( CollisionPair(co1,co2) ); }
       
-- 
GitLab