diff --git a/src/algorithm/geometry.hxx b/src/algorithm/geometry.hxx
index 5d3aafaa43e79215b42d3a0b7ba44aa9e91e8096..1a01bbb536456ed550a7ce9b94f3a38f48a2087e 100644
--- a/src/algorithm/geometry.hxx
+++ b/src/algorithm/geometry.hxx
@@ -207,7 +207,7 @@ namespace se3
     BOOST_FOREACH(const GeometryObject & geom,geomModel.geometryObjects)
     {
       const boost::shared_ptr<const fcl::CollisionGeometry> & fcl
-        = geom.collision_geometry;
+        = geom.fcl;
       const SE3 & jMb = geom.placement; // placement in joint.
       const Model::JointIndex & i = geom.parentJoint;
       assert (i<geomData.radius.size());
diff --git a/src/multibody/fcl.hpp b/src/multibody/fcl.hpp
index 3517532c4d92089c783ef0e7cc42a649594c0c9a..1587e4b5a09b248ba39612c4803ed48e79431e75 100644
--- a/src/multibody/fcl.hpp
+++ b/src/multibody/fcl.hpp
@@ -99,23 +99,23 @@ struct GeometryObject
   JointIndex parentJoint;
 
   /// \brief The actual cloud of points representing the collision mesh of the object
-  boost::shared_ptr<fcl::CollisionGeometry> collision_geometry;
+  boost::shared_ptr<fcl::CollisionGeometry> fcl;
 
   /// \brief Position of geometry object in parent joint frame
   SE3 placement;
 
   /// \brief Absolute path to the mesh file
-  std::string mesh_path;
+  std::string meshPath;
 
   GeometryObject(const std::string & name, const FrameIndex parentF,
                  const JointIndex parentJ, const boost::shared_ptr<fcl::CollisionGeometry> & collision,
-                 const SE3 & placement, const std::string & mesh_path)
+                 const SE3 & placement, const std::string & meshPath)
                 : name(name)
                 , parentFrame(parentF)
                 , parentJoint(parentJ)
-                , collision_geometry(collision)
+                , fcl(collision)
                 , placement(placement)
-                , mesh_path(mesh_path)
+                , meshPath(meshPath)
   {}
 
   GeometryObject & operator=(const GeometryObject & other)
@@ -123,13 +123,13 @@ struct GeometryObject
     name                = other.name;
     parentFrame         = other.parentFrame;
     parentJoint         = other.parentJoint;
-    collision_geometry  = other.collision_geometry;
+    fcl                 = other.fcl;
     placement           = other.placement;
-    mesh_path           = other.mesh_path;
+    meshPath            = other.meshPath;
     return *this;
   }
 
-  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geom_object);
+  friend std::ostream & operator<< (std::ostream & os, const GeometryObject & geomObject);
 };
   
 
diff --git a/src/multibody/fcl.hxx b/src/multibody/fcl.hxx
index 0769099b531f491108022303b40dfe6eeb20efcb..95a7d26ac670d063b74b18465b533246a7d32744 100644
--- a/src/multibody/fcl.hxx
+++ b/src/multibody/fcl.hxx
@@ -63,16 +63,15 @@ namespace se3
   }
   
 #endif // WITH_HPP_FCL
-
   
   inline bool operator==(const GeometryObject & lhs, const GeometryObject & rhs)
   {
-    return ( lhs.name == rhs.name
-            && lhs.parentFrame == rhs.parentFrame
-            && lhs.parentJoint == rhs.parentJoint
-            && lhs.collision_geometry == rhs.collision_geometry
-            && lhs.placement == rhs.placement
-            && lhs.mesh_path ==  rhs.mesh_path
+    return ( lhs.name           == rhs.name
+            && lhs.parentFrame  == rhs.parentFrame
+            && lhs.parentJoint  == rhs.parentJoint
+            && lhs.fcl          == rhs.fcl
+            && lhs.placement    == rhs.placement
+            && lhs.meshPath     == rhs.meshPath
             );
   }
 
@@ -81,9 +80,8 @@ namespace se3
     os  << "Name: \t \n" << geom_object.name << "\n"
         << "Parent frame ID: \t \n" << geom_object.parentFrame << "\n"
         << "Parent joint ID: \t \n" << geom_object.parentJoint << "\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"
+        << "Absolute path to mesh file: \t \n" << geom_object.meshPath << "\n"
         << std::endl;
     return os;
   }
diff --git a/src/multibody/geometry.hpp b/src/multibody/geometry.hpp
index 2da6efe8b33958dcb40da2494d18f6c761c6b545..b5da2c31ad317c7aa93f698744087f991d5257fc 100644
--- a/src/multibody/geometry.hpp
+++ b/src/multibody/geometry.hpp
@@ -74,14 +74,14 @@ namespace se3
      * @param[in]  co         The actual fcl CollisionGeometry
      * @param[in]  placement  The relative placement regarding to the parent frame
      * @param[in]  geom_name  The name of the Geometry Object
-     * @param[in]  mesh_path  The absolute path to the mesh
+     * @param[in]  meshPath   The absolute path to the mesh
      *
      * @return     The index of the new added GeometryObject in geometryObjects
      */
     inline GeomIndex addGeometryObject(const Model& model,
                                        const FrameIndex 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);
+                                       const std::string & meshPath = "") throw(std::invalid_argument);
 
 
 
diff --git a/src/multibody/geometry.hxx b/src/multibody/geometry.hxx
index 41dee30a8eb513bba5c5e72a6cfac85e11b411da..e604d5e310460aa51401e1dd4811a764a8b6563d 100644
--- a/src/multibody/geometry.hxx
+++ b/src/multibody/geometry.hxx
@@ -48,7 +48,7 @@ namespace se3
     collisionObjects.reserve(modelGeom.geometryObjects.size());
     BOOST_FOREACH( const GeometryObject & geom, modelGeom.geometryObjects)
       { collisionObjects.push_back
-          (fcl::CollisionObject(geom.collision_geometry)); }
+          (fcl::CollisionObject(geom.fcl)); }
     fillInnerOuterObjectMaps(modelGeom);
   }
 #else
@@ -67,12 +67,12 @@ namespace se3
                                                     const boost::shared_ptr<fcl::CollisionGeometry> & co,
                                                     const SE3 & placement,
                                                     const std::string & geom_name,
-                                                    const std::string & mesh_path) throw(std::invalid_argument)
+                                                    const std::string & meshPath) throw(std::invalid_argument)
   {
     assert (model.frames[parent].type == se3::BODY);
     JointIndex parentJoint = model.frames[parent].parent;
     GeometryObject object( geom_name, parent, parentJoint, co,
-                           placement, mesh_path);
+                           placement, meshPath);
     return addGeometryObject (object);
   }
 
diff --git a/src/parsers/urdf/geometry.cpp b/src/parsers/urdf/geometry.cpp
index 2967ccd79617e9293ca84209678c873f34f91c79..eb57fd9781f3101f8ce12f706a8c1d4c0e6e759e 100644
--- a/src/parsers/urdf/geometry.cpp
+++ b/src/parsers/urdf/geometry.cpp
@@ -48,13 +48,13 @@ namespace se3
      *
      * @param[in]  urdf_geometry  A shared pointer on the input urdf Geometry
      * @param[in]  package_dirs   A vector containing the different directories where to search for packages
-     * @param[out] mesh_path      The Absolute path of the mesh currently read
+     * @param[out] meshPath      The Absolute path of the mesh currently read
      *
      * @return     A shared pointer on the he geometry converted as a fcl::CollisionGeometry
      */
      boost::shared_ptr<fcl::CollisionGeometry> retrieveCollisionGeometry(const boost::shared_ptr< ::urdf::Geometry> urdf_geometry,
                                                                          const std::vector<std::string> & package_dirs,
-                                                                         std::string & mesh_path)
+                                                                         std::string & meshPath)
       {
         boost::shared_ptr<fcl::CollisionGeometry> geometry;
 
@@ -64,7 +64,7 @@ namespace se3
           boost::shared_ptr < ::urdf::Mesh> collisionGeometry = boost::dynamic_pointer_cast< ::urdf::Mesh> (urdf_geometry);
           std::string collisionFilename = collisionGeometry->filename;
 
-          mesh_path = retrieveResourcePath(collisionFilename, package_dirs);
+          meshPath = retrieveResourcePath(collisionFilename, package_dirs);
 
           fcl::Vec3f scale = fcl::Vec3f(collisionGeometry->scale.x,
                                               collisionGeometry->scale.y,
@@ -74,7 +74,7 @@ namespace se3
           // Create FCL mesh by parsing Collada file.
           PolyhedronPtrType polyhedron (new PolyhedronType);
 
-          fcl::loadPolyhedronFromResource (mesh_path, scale, polyhedron);
+          fcl::loadPolyhedronFromResource (meshPath, scale, polyhedron);
           geometry = polyhedron;
         }
 
@@ -82,7 +82,7 @@ namespace se3
         // Use FCL capsules for cylinders
         else if (urdf_geometry->type == ::urdf::Geometry::CYLINDER)
         {
-          mesh_path = "CYLINDER";
+          meshPath = "CYLINDER";
           boost::shared_ptr < ::urdf::Cylinder> collisionGeometry = boost::dynamic_pointer_cast< ::urdf::Cylinder> (urdf_geometry);
     
           double radius = collisionGeometry->radius;
@@ -94,7 +94,7 @@ namespace se3
         // Handle the case where collision geometry is a box.
         else if (urdf_geometry->type == ::urdf::Geometry::BOX) 
         {
-          mesh_path = "BOX";
+          meshPath = "BOX";
           boost::shared_ptr < ::urdf::Box> collisionGeometry = boost::dynamic_pointer_cast< ::urdf::Box> (urdf_geometry);
     
           double x = collisionGeometry->dim.x;
@@ -106,7 +106,7 @@ namespace se3
         // Handle the case where collision geometry is a sphere.
         else if (urdf_geometry->type == ::urdf::Geometry::SPHERE)
         {
-          mesh_path = "SPHERE";
+          meshPath = "SPHERE";
           boost::shared_ptr < ::urdf::Sphere> collisionGeometry = boost::dynamic_pointer_cast< ::urdf::Sphere> (urdf_geometry);
 
           double radius = collisionGeometry->radius;
@@ -186,7 +186,7 @@ namespace se3
       {
         if(getLinkGeometry<T>(link))
         {
-          std::string mesh_path = "";
+          std::string meshPath = "";
         
           std::string link_name = link->name;
 
@@ -201,12 +201,12 @@ namespace se3
           std::size_t objectId = 0;
           for (typename std::vector< boost::shared_ptr< T > >::const_iterator i = geometries_array.begin();i != geometries_array.end(); ++i)
           {
-            mesh_path.clear();
+            meshPath.clear();
 #ifdef WITH_HPP_FCL
-            const boost::shared_ptr<fcl::CollisionGeometry> geometry = retrieveCollisionGeometry((*i)->geometry, package_dirs, mesh_path);
+            const boost::shared_ptr<fcl::CollisionGeometry> geometry = retrieveCollisionGeometry((*i)->geometry, package_dirs, meshPath);
 #else
             boost::shared_ptr < ::urdf::Mesh> urdf_mesh = boost::dynamic_pointer_cast< ::urdf::Mesh> ((*i)->geometry);
-            if (urdf_mesh) mesh_path = retrieveResourcePath(urdf_mesh->filename, package_dirs);
+            if (urdf_mesh) meshPath = retrieveResourcePath(urdf_mesh->filename, package_dirs);
             
             const boost::shared_ptr<fcl::CollisionGeometry> geometry(new fcl::CollisionGeometry());
 #endif // WITH_HPP_FCL            
@@ -215,7 +215,7 @@ namespace se3
             std::ostringstream geometry_object_suffix;
             geometry_object_suffix << "_" << objectId;
             const std::string & geometry_object_name = std::string(link_name + geometry_object_suffix.str());
-            geom_model.addGeometryObject(model, frame_id, geometry, geomPlacement, geometry_object_name, mesh_path);
+            geom_model.addGeometryObject(model, frame_id, geometry, geomPlacement, geometry_object_name, meshPath);
             ++objectId; 
           }
         }