diff --git a/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h b/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
index 18811c7cb0fdccc5e2a8fc39aa349dae4a3b9677..fda38f99323f5b9a05a7f7e4d8aa0a0a173a787f 100644
--- a/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
+++ b/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
@@ -1,7 +1,7 @@
 template <typename Derived>
 IVector3& operator=(const FclType<Derived>& other)
 {
-  const Vec3f& tmp = other.derived();
+  const Vec3f& tmp = other.fcl();
   setValue (tmp);
   return *this;
 }
diff --git a/include/hpp/fcl/eigen/vec_3fx.h b/include/hpp/fcl/eigen/vec_3fx.h
index 94a9829d41a4604542cfdeaebf725e293091d716..338567d4d32de24fe3e5c17047f701caa9ef62e2 100644
--- a/include/hpp/fcl/eigen/vec_3fx.h
+++ b/include/hpp/fcl/eigen/vec_3fx.h
@@ -133,8 +133,8 @@ template <typename Derived>
 class FclType
 {
   public:
-    Derived& derived () { return static_cast<Derived&> (*this); }
-    const Derived& derived () const { return static_cast<const Derived&> (*this); }
+    Derived& fcl () { return static_cast<Derived&> (*this); }
+    const Derived& fcl () const { return static_cast<const Derived&> (*this); }
 };
 }
 
@@ -209,7 +209,7 @@ namespace Eigen {
 #define FCL_EIGEN_CURRENT_CLASS FclMatrix
 
 /// @brief Vector3 class wrapper. The core data is in the template parameter class.
-template <typename T, int Cols, int _Options>
+template <typename T, int Cols, int _Options = internal::traits<Matrix <T, 3, Cols> >::Options >
 class FclMatrix : public Matrix <T, 3, Cols, _Options>, public ::fcl::FclType<FclMatrix <T, Cols, _Options> >
 {
 public:
@@ -255,9 +255,9 @@ public:
             const ::fcl::FclType<Vector>& r1,
             const ::fcl::FclType<Vector>& r2) : Base()
   {
-    this->row(0) = r0.derived();
-    this->row(1) = r1.derived();
-    this->row(2) = r2.derived();
+    this->row(0) = r0.fcl();
+    this->row(1) = r1.fcl();
+    this->row(2) = r2.fcl();
   }
 
   /// @brief create vector (x, x, x)
@@ -563,7 +563,7 @@ public:
   inline const typename UnaryReturnType<EigenOp>::Abs
     abs() const
   {
-    return typename UnaryReturnType<EigenOp>::Abs (this->derived());
+    return typename UnaryReturnType<EigenOp>::Abs (*this);
   }
 
   inline Scalar length() const { return this->norm(); }
@@ -638,21 +638,21 @@ template<typename Derived, typename OtherDerived>
 static inline const typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Min
  min(const FclType<Derived>& x, const FclType<OtherDerived>& y)
 {
-  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Min (x.derived(), y.derived());
+  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Min (x.fcl(), y.fcl());
 }
 
 template<typename Derived, typename OtherDerived>
 static inline const typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Max
  max(const FclType<Derived>& x, const FclType<OtherDerived>& y)
 {
-  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Max (x.derived(), y.derived());
+  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Max (x.fcl(), y.fcl());
 }
 
 template<typename Derived>
 static inline const typename Eigen::UnaryReturnType<const Derived>::Abs
 abs(const FclType<Derived>& x)
 {
-  return typename Eigen::UnaryReturnType<const Derived>::Abs (x.derived());
+  return typename Eigen::UnaryReturnType<const Derived>::Abs (x.fcl());
 }
 
 template<typename Derived>
@@ -663,9 +663,9 @@ void generateCoordinateSystem(
 {
   typedef typename Derived::Scalar T;
 
-  Derived& w = _w.derived();
-  Derived& u = _u.derived();
-  Derived& v = _v.derived();
+  Derived& w = _w.fcl();
+  Derived& u = _u.fcl();
+  Derived& v = _v.fcl();
 
   T inv_length;
   if(std::abs(w[0]) >= std::abs(w[1]))
@@ -720,7 +720,7 @@ template<typename Matrix, typename Vector>
 void eigen(const FclType<Matrix>& m, typename Matrix::Scalar dout[3], Vector* vout)
 {
   typedef typename Matrix::Scalar Scalar;
-  Matrix R(m.derived());
+  Matrix R(m.fcl());
   int n = 3;
   int j, iq, ip, i;
   Scalar tresh, theta, tau, t, sm, s, h, g, c;
@@ -805,10 +805,10 @@ void eigen(const FclType<Matrix>& m, typename Matrix::Scalar dout[3], Vector* vo
   return;
 }
 
-template<typename T, int _Options>
-Eigen::FclOp<Eigen::Transpose<const Eigen::FclMatrix<T,3,_Options> > > transpose(const Eigen::FclMatrix<T, 3, _Options>& R)
+template<typename Derived>
+Eigen::FclOp<Eigen::Transpose<const Derived> > transpose(const FclType<Derived>& R)
 {
-  return Eigen::FclOp<Eigen::Transpose<const Eigen::FclMatrix<T,3,_Options> > > (R);
+  return Eigen::FclOp<Eigen::Transpose<const Derived > > (R.fcl());
 }
 
 template<typename T, int _Options>
diff --git a/include/hpp/fcl/math/matrix_3f.h b/include/hpp/fcl/math/matrix_3f.h
index b43b5d6c6ac0a18003769c29548fc55bddb7d521..a44118f68a191cd3b00170af27ca30c466903ff8 100644
--- a/include/hpp/fcl/math/matrix_3f.h
+++ b/include/hpp/fcl/math/matrix_3f.h
@@ -49,7 +49,7 @@ namespace fcl
 
 #if FCL_HAVE_EIGEN
 # if FCL_USE_NATIVE_EIGEN
-  typedef Eigen::FclMatrix<FCL_REAL, 3, 0> Matrix3f;
+  typedef Eigen::FclMatrix<FCL_REAL, 3> Matrix3f;
 # else
   typedef Matrix3fX<details::eigen_wrapper_m3<FCL_REAL> > Matrix3f;
 # endif
diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h
index 5b1be28bb0bc12d748b4bfe8f7eee130bb22f6fd..0cf42198d6b54f3596193ce0c07f79d76fa45618 100644
--- a/include/hpp/fcl/math/vec_3f.h
+++ b/include/hpp/fcl/math/vec_3f.h
@@ -67,7 +67,7 @@ namespace fcl
 
 #if FCL_HAVE_EIGEN
 # if FCL_USE_NATIVE_EIGEN
-  typedef Eigen::FclMatrix<FCL_REAL, 1, 0> Vec3f;
+  typedef Eigen::FclMatrix<FCL_REAL, 1> Vec3f;
 # else
   typedef Vec3fX<details::eigen_wrapper_v3<FCL_REAL> > Vec3f;
 # endif