From 405a4b836de20f7d3effaf70f67e64a5c1db8b75 Mon Sep 17 00:00:00 2001
From: Joseph Mirabel <jmirabel@laas.fr>
Date: Fri, 10 Jun 2016 19:58:46 +0200
Subject: [PATCH] Clean code and remove unused files.

---
 CMakeLists.txt                                |    3 +-
 include/hpp/fcl/ccd/interval_matrix.h         |    4 -
 include/hpp/fcl/ccd/interval_vector.h         |   12 +-
 include/hpp/fcl/ccd/taylor_vector.h           |   18 +-
 include/hpp/fcl/eigen/math_details.h          |  767 -----------
 .../fcl/eigen/plugins/ccd/interval-matrix.h   |    0
 .../fcl/eigen/plugins/ccd/interval-vector.h   |    7 -
 include/hpp/fcl/eigen/product.h               |   39 -
 include/hpp/fcl/eigen/taylor_operator.h       |   25 -
 include/hpp/fcl/eigen/vec_3fx.h               |  770 -----------
 include/hpp/fcl/math/math_details.h           |  501 --------
 include/hpp/fcl/math/matrix_3f.h              |   22 -
 include/hpp/fcl/math/matrix_3fx.h             |  481 -------
 include/hpp/fcl/math/tools.h                  |   26 -
 include/hpp/fcl/math/vec_3f.h                 |   25 -
 include/hpp/fcl/math/vec_3fx.h                |  245 ----
 include/hpp/fcl/simd/math_simd_details.h      | 1143 -----------------
 include/hpp/fcl/simd/simd_intersect.h         |  243 ----
 18 files changed, 24 insertions(+), 4307 deletions(-)
 delete mode 100644 include/hpp/fcl/eigen/math_details.h
 delete mode 100644 include/hpp/fcl/eigen/plugins/ccd/interval-matrix.h
 delete mode 100644 include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
 delete mode 100644 include/hpp/fcl/eigen/product.h
 delete mode 100644 include/hpp/fcl/eigen/taylor_operator.h
 delete mode 100644 include/hpp/fcl/eigen/vec_3fx.h
 delete mode 100644 include/hpp/fcl/math/math_details.h
 delete mode 100644 include/hpp/fcl/math/matrix_3fx.h
 delete mode 100644 include/hpp/fcl/math/vec_3fx.h
 delete mode 100644 include/hpp/fcl/simd/math_simd_details.h
 delete mode 100644 include/hpp/fcl/simd/simd_intersect.h

diff --git a/CMakeLists.txt b/CMakeLists.txt
index d0e5356c..fa2b020f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -48,9 +48,8 @@ setup_project()
 
 set(FCL_HAVE_SSE FALSE CACHE BOOL "Enable SSE vectorization")
 
-# add_optional_dependency("eigen3 >= 3.0.0")
 add_required_dependency("eigen3 >= 3.0.0")
-set(FCL_HAVE_EIGEN TRUE CACHE BOOL "Use eigen matrix type when possible")
+set(FCL_HAVE_EIGEN TRUE)
 include_directories(${EIGEN3_INCLUDE_DIRS})
 
 # Required dependencies
diff --git a/include/hpp/fcl/ccd/interval_matrix.h b/include/hpp/fcl/ccd/interval_matrix.h
index 6ad14b0d..f828387a 100644
--- a/include/hpp/fcl/ccd/interval_matrix.h
+++ b/include/hpp/fcl/ccd/interval_matrix.h
@@ -99,10 +99,6 @@ struct IMatrix3
   IMatrix3& rotationConstrain();
 
   void print() const;
-
-#ifdef FCL_CCD_INTERVALMATRIX_PLUGIN
-# include FCL_CCD_INTERVALMATRIX_PLUGIN
-#endif
 };
 
 IMatrix3 rotationConstrain(const IMatrix3& m);
diff --git a/include/hpp/fcl/ccd/interval_vector.h b/include/hpp/fcl/ccd/interval_vector.h
index 7c1216b9..a996f041 100644
--- a/include/hpp/fcl/ccd/interval_vector.h
+++ b/include/hpp/fcl/ccd/interval_vector.h
@@ -157,9 +157,15 @@ struct IVector3
   bool overlap(const IVector3& v) const;
   bool contain(const IVector3& v) const;
 
-#ifdef FCL_CCD_INTERVALVECTOR_PLUGIN
-# include FCL_CCD_INTERVALVECTOR_PLUGIN
-#endif
+  template <typename Derived>
+  IVector3& operator=(const Eigen::MatrixBase<Derived>& other)
+  {
+    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3); \
+    setValue (other.derived());
+    // const Vec3f& tmp (other);
+    // setValue (tmp);
+    return *this;
+  }
 };
 
 IVector3 bound(const IVector3& i, const Vec3f& v);
diff --git a/include/hpp/fcl/ccd/taylor_vector.h b/include/hpp/fcl/ccd/taylor_vector.h
index be570a38..fedd6c11 100644
--- a/include/hpp/fcl/ccd/taylor_vector.h
+++ b/include/hpp/fcl/ccd/taylor_vector.h
@@ -40,10 +40,8 @@
 
 #include <hpp/fcl/ccd/interval_vector.h>
 #include <hpp/fcl/ccd/taylor_model.h>
-
-#if FCL_HAVE_EIGEN
-#include <hpp/fcl/eigen/taylor_operator.h>
-#endif
+#include <hpp/fcl/math/vec_3f.h>
+#include <hpp/fcl/math/matrix_3f.h>
 
 namespace fcl
 {
@@ -106,8 +104,20 @@ public:
   const boost::shared_ptr<TimeInterval>& getTimeInterval() const;
 };
 
+class TMatrix3;
+
 void generateTVector3ForLinearFunc(TVector3& v, const Vec3f& position, const Vec3f& velocity);
 
+template<int Col> struct TaylorReturnType {};
+template<> struct TaylorReturnType<1> { typedef TVector3 type; typedef Vec3f    eigen_type; };
+template<> struct TaylorReturnType<3> { typedef TMatrix3 type; typedef Matrix3f eigen_type; };
+
+template<typename Derived>
+typename TaylorReturnType<Derived::ColsAtCompileTime>::type operator * (const Eigen::MatrixBase<Derived>& v, const TaylorModel& a)
+{
+  const typename TaylorReturnType<Derived::ColsAtCompileTime>::eigen_type b = v.derived();
+  return b * a;
+}
 
 TVector3 operator * (const Vec3f& v, const TaylorModel& a);
 TVector3 operator + (const Vec3f& v1, const TVector3& v2);
diff --git a/include/hpp/fcl/eigen/math_details.h b/include/hpp/fcl/eigen/math_details.h
deleted file mode 100644
index 0f2437da..00000000
--- a/include/hpp/fcl/eigen/math_details.h
+++ /dev/null
@@ -1,767 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Joseph Mirabel */
-
-#ifndef FCL_EIGEN_DETAILS_H
-#define FCL_EIGEN_DETAILS_H
-
-#include <Eigen/Dense>
-#include <Eigen/Geometry>
-
-namespace fcl
-{
-
-namespace details
-{
-
-template <typename T>
-struct eigen_wrapper_v3
-{
-  typedef T meta_type;
-  typedef Eigen::Matrix <T, 3, 1> vector_type;
-
-  vector_type v;
-
-  eigen_wrapper_v3() { setValue(0); }
-
-  template <typename Derived>
-    eigen_wrapper_v3(const Eigen::MatrixBase <Derived>& value) :
-      v (value)
-  {}
-
-  eigen_wrapper_v3(T x) :
-    v (vector_type::Constant (x))
-  {}
-
-  eigen_wrapper_v3(T* x) :
-    v (vector_type::Constant (*x))
-  {}
-
-  eigen_wrapper_v3(T x, T y, T z) :
-    v (x, y, z)
-  {}
-
-  inline void setValue(T x, T y, T z)
-  {
-    v << x, y, z;
-  }
-
-  inline void setValue(T x)
-  {
-    v.setConstant (x);
-  }
-
-  inline eigen_wrapper_v3<T>& ubound(const eigen_wrapper_v3<T>& u)
-  {
-    v = v.cwiseMin (u.v);
-    return *this;
-  }
-
-  inline eigen_wrapper_v3<T>& lbound(const eigen_wrapper_v3<T>& l)
-  {
-    v = v.cwiseMax (l.v);
-    return *this;
-  }
-
-  T operator [] (size_t i) const { return v[i]; }
-  T& operator [] (size_t i) { return v[i]; }
-
-  inline eigen_wrapper_v3<T> operator + (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v + other.v); }
-  inline eigen_wrapper_v3<T> operator - (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v - other.v); }
-  inline eigen_wrapper_v3<T> operator * (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v.cwiseProduct (other.v)); }
-  inline eigen_wrapper_v3<T> operator / (const eigen_wrapper_v3<T>& other) const { return (eigen_wrapper_v3<T>(v) /= other); }
-  inline eigen_wrapper_v3<T>& operator += (const eigen_wrapper_v3<T>& other) { v += other.v; return *this; }
-  inline eigen_wrapper_v3<T>& operator -= (const eigen_wrapper_v3<T>& other) { v -= other.v; return *this; }
-  inline eigen_wrapper_v3<T>& operator *= (const eigen_wrapper_v3<T>& other) { v = v.cwiseProduct  (other.v); return *this; }
-  inline eigen_wrapper_v3<T>& operator /= (const eigen_wrapper_v3<T>& other) { v = v.cwiseQuotient (other.v); return *this; }
-  inline eigen_wrapper_v3<T> operator + (T t) const { return eigen_wrapper_v3<T>((v.array() + t).matrix()); }
-  inline eigen_wrapper_v3<T> operator - (T t) const { return eigen_wrapper_v3<T>((v.array() - t).matrix()); }
-  inline eigen_wrapper_v3<T> operator * (T t) const { return eigen_wrapper_v3<T>(v * t); }
-  inline eigen_wrapper_v3<T> operator / (T t) const { return eigen_wrapper_v3<T>(v / t); }
-  inline eigen_wrapper_v3<T>& operator += (T t) { v.array() += t; return *this; }
-  inline eigen_wrapper_v3<T>& operator -= (T t) { v.array() -= t; return *this; }
-  inline eigen_wrapper_v3<T>& operator *= (T t) { v.array() *= t; return *this; }
-  inline eigen_wrapper_v3<T>& operator /= (T t) { v.array() /= t; return *this; }
-  inline eigen_wrapper_v3<T> operator - () const { return eigen_wrapper_v3<T>(-v); }
-};
-
-
-template <typename T>
-static inline eigen_wrapper_v3<T> cross_prod(const eigen_wrapper_v3<T>& l, const eigen_wrapper_v3<T>& r)
-{
-  return eigen_wrapper_v3<T>(l.v.cross (r.v));
-}
-
-template <typename T>
-static inline T dot_prod3(const eigen_wrapper_v3<T>& l, const eigen_wrapper_v3<T>& r)
-{
-  return l.v.dot(r.v);
-}
-
-template <typename T>
-static inline eigen_wrapper_v3<T> min(const eigen_wrapper_v3<T>& x, const eigen_wrapper_v3<T>& y)
-{
-  return eigen_wrapper_v3<T>(x.v.cwiseMin (y.v));
-}
-
-template <typename T>
-static inline eigen_wrapper_v3<T> max(const eigen_wrapper_v3<T>& x, const eigen_wrapper_v3<T>& y)
-{
-  return eigen_wrapper_v3<T>(x.v.cwiseMax(y.v));
-}
-
-template <typename T>
-static inline eigen_wrapper_v3<T> abs(const eigen_wrapper_v3<T>& x)
-{
-  return eigen_wrapper_v3<T>(x.v.cwiseAbs());
-}
-
-template <typename T>
-static inline bool equal(const eigen_wrapper_v3<T>& x, const eigen_wrapper_v3<T>& y, T epsilon)
-{
-  return ((x.v - y.v).cwiseAbs ().array () < epsilon).all();
-}
-
-namespace internal {
-  template <typename Derived, int Size> struct assign {
-    static Eigen::Matrix<typename Derived::Scalar, 4, 1> run (const Eigen::MatrixBase <Derived>& value)
-    {
-      assert (false);
-    }
-  };
-
-  template <typename Derived> struct assign <Derived, 3> {
-    static Eigen::Matrix<typename Derived::Scalar, 4, 1> run (const Eigen::MatrixBase <Derived>& value)
-    {
-      return (Eigen::Matrix<typename Derived::Scalar, 4, 1> () << value, 0).finished ();
-    }
-  };
-
-  template <typename Derived> struct assign <Derived, 4> {
-    static Eigen::Matrix<typename Derived::Scalar, 4, 1> run (const Eigen::MatrixBase <Derived>& value)
-    {
-      return value;
-    }
-  };
-}
-
-template <typename T>
-struct eigen_wrapper_v4
-{
-  typedef T meta_type;
-  typedef Eigen::Matrix <T, 4, 1> vector_type;
-
-  vector_type v;
-
-  eigen_wrapper_v4() { setValue(0); }
-
-  template <typename Derived>
-    eigen_wrapper_v4(const Eigen::MatrixBase <Derived>& value) :
-      v (internal::assign <Derived, Derived::SizeAtCompileTime>::run (value))
-  {}
-
-  eigen_wrapper_v4(T x) :
-    v (vector_type::Constant (x))
-  {
-    v[3] = 0;
-  }
-
-  eigen_wrapper_v4(T* x) :
-    v (vector_type::Constant (*x))
-  {
-    v[3] = 0;
-  }
-
-  eigen_wrapper_v4(T x, T y, T z) :
-    v (x, y, z, 0)
-  {}
-
-  inline typename vector_type::template FixedSegmentReturnType<3>::Type d () { return v.template head <3> (); }
-
-  inline typename vector_type::template ConstFixedSegmentReturnType<3>::Type d () const { return v.template head <3> (); }
-
-  inline void setValue(T x, T y, T z, T w = 0)
-  {
-    v << x, y, z, w;
-  }
-
-  inline void setValue(T x)
-  {
-    d().setConstant (x);
-    v[3] = 0;
-  }
-
-  inline eigen_wrapper_v4<T>& ubound(const eigen_wrapper_v4<T>& u)
-  {
-    v = v.cwiseMin (u.v);
-    return *this;
-  }
-
-  inline eigen_wrapper_v4<T>& lbound(const eigen_wrapper_v4<T>& l)
-  {
-    v = v.cwiseMax (l.v);
-    return *this;
-  }
-
-  T operator [] (size_t i) const { return v[i]; }
-  T& operator [] (size_t i) { return v[i]; }
-
-  inline eigen_wrapper_v4<T> operator + (const eigen_wrapper_v4<T>& other) const { return eigen_wrapper_v4<T>(v + other.v); }
-  inline eigen_wrapper_v4<T> operator - (const eigen_wrapper_v4<T>& other) const { return eigen_wrapper_v4<T>(v - other.v); }
-  inline eigen_wrapper_v4<T> operator * (const eigen_wrapper_v4<T>& other) const { return eigen_wrapper_v4<T>(v.cwiseProduct (other.v)); }
-  inline eigen_wrapper_v4<T> operator / (const eigen_wrapper_v4<T>& other) const { return (eigen_wrapper_v4<T>(v) /= other); }
-  inline eigen_wrapper_v4<T>& operator += (const eigen_wrapper_v4<T>& other) { v += other.v; return *this; }
-  inline eigen_wrapper_v4<T>& operator -= (const eigen_wrapper_v4<T>& other) { v -= other.v; return *this; }
-  inline eigen_wrapper_v4<T>& operator *= (const eigen_wrapper_v4<T>& other) { v = v.cwiseProduct  (other.v); return *this; }
-  inline eigen_wrapper_v4<T>& operator /= (const eigen_wrapper_v4<T>& other) { d() = d().cwiseQuotient (other.d()); return *this; }
-  inline eigen_wrapper_v4<T> operator + (T t) const { return eigen_wrapper_v4<T>((d().array() + t).matrix()); }
-  inline eigen_wrapper_v4<T> operator - (T t) const { return eigen_wrapper_v4<T>((d().array() - t).matrix()); }
-  inline eigen_wrapper_v4<T> operator * (T t) const { return eigen_wrapper_v4<T>(v * t); }
-  inline eigen_wrapper_v4<T> operator / (T t) const { return eigen_wrapper_v4<T>(v / t); }
-  inline eigen_wrapper_v4<T>& operator += (T t) { d().array() += t; return *this; }
-  inline eigen_wrapper_v4<T>& operator -= (T t) { d().array() -= t; return *this; }
-  inline eigen_wrapper_v4<T>& operator *= (T t) { v.array() *= t; return *this; }
-  inline eigen_wrapper_v4<T>& operator /= (T t) { v.array() /= t; return *this; }
-  inline eigen_wrapper_v4<T> operator - () const { return eigen_wrapper_v4<T>(-v); }
-} __attribute__ ((aligned));
-
-
-template <typename T>
-static inline eigen_wrapper_v4<T> cross_prod(const eigen_wrapper_v4<T>& l, const eigen_wrapper_v4<T>& r)
-{
-  return eigen_wrapper_v4<T>(l.v.cross3 (r.v));
-}
-
-template <typename T>
-static inline T dot_prod3(const eigen_wrapper_v4<T>& l, const eigen_wrapper_v4<T>& r)
-{
-  return l.v.dot(r.v);
-}
-
-template <typename T>
-static inline eigen_wrapper_v4<T> min(const eigen_wrapper_v4<T>& x, const eigen_wrapper_v4<T>& y)
-{
-  return eigen_wrapper_v4<T>(x.v.cwiseMin (y.v));
-}
-
-template <typename T>
-static inline eigen_wrapper_v4<T> max(const eigen_wrapper_v4<T>& x, const eigen_wrapper_v4<T>& y)
-{
-  return eigen_wrapper_v4<T>(x.v.cwiseMax(y.v));
-}
-
-template <typename T>
-static inline eigen_wrapper_v4<T> abs(const eigen_wrapper_v4<T>& x)
-{
-  return eigen_wrapper_v4<T>(x.v.cwiseAbs());
-}
-
-template <typename T>
-static inline bool equal(const eigen_wrapper_v4<T>& x, const eigen_wrapper_v4<T>& y, T epsilon)
-{
-  return ((x.v - y.v).cwiseAbs ().array () < epsilon).all();
-}
-
-template <typename T>
-struct eigen_v3 :
-  Eigen::Matrix <T, 3, 1>
-{
-  typedef T meta_type;
-  typedef Eigen::Matrix <T, 3, 1> Base;
-
-  eigen_v3(void): Base () { this->setZero (); }
-
-  // This constructor allows you to construct MyVectorType from Eigen expressions
-  template<typename OtherDerived>
-    eigen_v3(const Eigen::MatrixBase<OtherDerived>& other)
-    : Base(other)
-  {}
-
-  // This method allows you to assign Eigen expressions to MyVectorType
-  template<typename OtherDerived>
-    eigen_v3& operator= (const Eigen::MatrixBase <OtherDerived>& other)
-    {
-      this->Base::operator=(other);
-      return *this;
-    }
-
-  eigen_v3(T x) :
-    Base (x, x, x)
-  {}
-
-  eigen_v3(T* x) :
-    Base (*x, *x, *x)
-  {}
-
-  eigen_v3(T x, T y, T z) :
-    Base (x, y, z)
-  {}
-
-  inline void setValue(T x, T y, T z)
-  {
-    this->operator[] (0) = x;
-    this->operator[] (1) = y;
-    this->operator[] (2) = z;
-  }
-
-  inline void setValue(T x)
-  {
-    this->setConstant (x);
-  }
-
-  template<typename OtherDerived>
-  inline eigen_v3<T>& ubound(const Eigen::MatrixBase<OtherDerived>& u)
-  {
-    *this = this->cwiseMin (u);
-    return *this;
-  }
-
-  template<typename OtherDerived>
-  inline eigen_v3<T>& lbound(const Eigen::MatrixBase<OtherDerived>& l)
-  {
-    *this = this->cwiseMax (l);
-    return *this;
-  }
-
-  // T operator [] (size_t i) const { return v[i]; }
-  // T& operator [] (size_t i) { return v[i]; }
-
-  // inline eigen_wrapper_v3<T> operator + (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v + other.v); }
-  // inline eigen_wrapper_v3<T> operator - (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v[0] - other.v[0], v[1] - other.v[1], v[2] - other.v[2]); }
-  // inline eigen_wrapper_v3<T> operator * (const eigen_wrapper_v3<T>& other) const { return eigen_wrapper_v3<T>(v[0] * other.v[0], v[1] * other.v[1], v[2] * other.v[2]); }
-  // inline eigen_v3<T> operator / (const eigen_v3<T>& other) const { return eigen_v3<T>(this->array().cwiseQuotient (other)); }
-  inline eigen_v3<T>& operator += (const eigen_v3<T>& other) { return static_cast<eigen_v3<T>&>(this->Base::operator+= (other)); }
-  inline eigen_v3<T>& operator -= (const eigen_v3<T>& other) { return static_cast<eigen_v3<T>&>(this->Base::operator-= (other)); }
-  inline eigen_v3<T>& operator *= (const eigen_v3<T>& other) { return static_cast<eigen_v3<T>&>(this->array().operator*=(other)); }
-  inline eigen_v3<T>& operator /= (const eigen_v3<T>& other) { return static_cast<eigen_v3<T>&>(this->array().operator/=(other)); }
-  // inline eigen_wrapper_v4<T>& operator /= (const eigen_wrapper_v4<T>& other) {  = d().cwiseQuotient (other.d()); return *this; }
-  // inline eigen_wrapper_v3<T>& operator *= (const eigen_wrapper_v3<T>& other) { return this->Base::operator*= (other); }
-  // inline eigen_wrapper_v3<T>& operator /= (const eigen_wrapper_v3<T>& other) { return this->Base::operator/= (other); }
-  // inline eigen_wrapper_v3<T> operator + (T t) const { return eigen_wrapper_v3<T>(v + t); }
-  // inline eigen_wrapper_v3<T> operator - (T t) const { return eigen_wrapper_v3<T>(v - t); }
-  // inline eigen_wrapper_v3<T> operator * (T t) const { return eigen_wrapper_v3<T>(v * t); }
-  // inline eigen_wrapper_v3<T> operator / (T t) const { return eigen_wrapper_v3<T>(v / t); }
-  inline eigen_v3<T>& operator += (T t) { this->array() += t; return *this; }
-  inline eigen_v3<T>& operator -= (T t) { this->array() -= t; return *this; }
-  inline eigen_v3<T>& operator *= (T t) { this->array() *= t; return *this; }
-  inline eigen_v3<T>& operator /= (T t) { this->array() /= t; return *this; }
-  // inline eigen_wrapper_v3<T> operator - () const { return eigen_wrapper_v3<T>(-v); }
-};
-
-
-template <typename T>
-static inline eigen_v3<T> cross_prod(const eigen_v3<T>& l, const eigen_v3<T>& r)
-{
-  return l.cross (r);
-}
-
-template <typename T>
-static inline T dot_prod3(const eigen_v3<T>& l, const eigen_v3<T>& r)
-{
-  return l.dot(r);
-}
-
-template <typename T>
-static inline eigen_v3<T> min(const eigen_v3<T>& x, const eigen_v3<T>& y)
-{
-  return x.cwiseMin (y);
-}
-
-template <typename T>
-static inline eigen_v3<T> max(const eigen_v3<T>& x, const eigen_v3<T>& y)
-{
-  return x.cwiseMax(y);
-}
-
-template <typename T>
-static inline eigen_v3<T> abs(const eigen_v3<T>& x)
-{
-  return x.cwiseAbs();
-}
-
-template <typename T>
-static inline bool equal(const eigen_v3<T>& x, const eigen_v3<T>& y, T epsilon)
-{
-  return ((x - y).cwiseAbs ().array () < epsilon).all();
-}
-
-template<typename T>
-struct eigen_wrapper_m3
-{
-  typedef T meta_type;
-  typedef eigen_wrapper_v3<T> vector_type;
-  typedef Eigen::Matrix <T, 3, 3, Eigen::RowMajor> matrix_type;
-  typedef Eigen::Matrix <T, 3, 1> inner_col_type;
-  typedef typename matrix_type::ConstRowXpr ConstRowXpr;
-
-  matrix_type m;
-  eigen_wrapper_m3() {};
-
-  template <typename Derived>
-    eigen_wrapper_m3(const Eigen::MatrixBase <Derived>& matrix) :
-      m (matrix)
-  {}
-
-  eigen_wrapper_m3(T xx, T xy, T xz,
-                   T yx, T yy, T yz,
-                   T zx, T zy, T zz)
-  {
-    setValue(xx, xy, xz,
-             yx, yy, yz,
-             zx, zy, zz);
-  }
-
-  eigen_wrapper_m3(const vector_type& v1, const vector_type& v2, const vector_type& v3)
-  {
-    m << v1.v, v2.v, v3.v;
-  }
-
-  eigen_wrapper_m3(const eigen_wrapper_m3<T>& other) { m = other.m; }
-
-  inline inner_col_type getColumn(size_t i) const { return m.col (i); }
-  inline ConstRowXpr getRow(size_t i) const { return m.row (i); }
-
-  inline T operator() (size_t i, size_t j) const { return m(i, j); }
-  inline T& operator() (size_t i, size_t j) { return m(i, j); }
-
-  inline vector_type operator * (const vector_type& v) const { return vector_type(m * v.v); }
-
-  inline eigen_wrapper_m3<T> operator * (const eigen_wrapper_m3<T>& other) const { return eigen_wrapper_m3<T>(m * other.m); }
-  inline eigen_wrapper_m3<T> operator + (const eigen_wrapper_m3<T>& other) const { return eigen_wrapper_m3<T>(m + other.m); }
-  inline eigen_wrapper_m3<T> operator - (const eigen_wrapper_m3<T>& other) const { return eigen_wrapper_m3<T>(m - other.m); }
-
-  inline eigen_wrapper_m3<T> operator + (T c) const { return eigen_wrapper_m3<T>(m + c); }
-  inline eigen_wrapper_m3<T> operator - (T c) const { return eigen_wrapper_m3<T>(m - c); }
-  inline eigen_wrapper_m3<T> operator * (T c) const { return eigen_wrapper_m3<T>(m * c); }
-  inline eigen_wrapper_m3<T> operator / (T c) const { return eigen_wrapper_m3<T>(m / c); }
-
-  inline eigen_wrapper_m3<T>& operator *= (const eigen_wrapper_m3<T>& other) { m *= other.m; return *this; }
-  inline eigen_wrapper_m3<T>& operator += (const eigen_wrapper_m3<T>& other) { m += other.m; return *this; }
-  inline eigen_wrapper_m3<T>& operator -= (const eigen_wrapper_m3<T>& other) { m -= other.m; return *this; }
-
-  inline eigen_wrapper_m3<T>& operator += (T c) { m.array() += c; return *this; }
-  inline eigen_wrapper_m3<T>& operator -= (T c) { m.array() -= c; return *this; }
-  inline eigen_wrapper_m3<T>& operator *= (T c) { m.array() *= c; return *this; }
-  inline eigen_wrapper_m3<T>& operator /= (T c) { m.array() /= c; return *this; }
-
-
-  void setIdentity() { m.setIdentity (); }
-
-  void setZero() { m.setZero(); }
-
-  static const eigen_wrapper_m3<T>& getIdentity()
-  {
-    static const eigen_wrapper_m3<T> I(matrix_type::Identity ());
-    return I;
-  }
-
-  T determinant() const { return m.determinant (); }
-
-  eigen_wrapper_m3<T>& transpose()
-  {
-    m.transposeInPlace ();
-    return *this;
-  }
-
-  eigen_wrapper_m3<T>& inverse()
-  {
-    m = m.inverse().eval();
-    return *this;
-  }
-
-  eigen_wrapper_m3<T> transposeTimes(const eigen_wrapper_m3<T>& other) const
-  {
-    return eigen_wrapper_m3<T>(m.transpose () * other.m);
-  }
-
-  eigen_wrapper_m3<T> timesTranspose(const eigen_wrapper_m3<T>& other) const
-  {
-    return eigen_wrapper_m3<T>(m * other.transpose ());
-  }
-
-  vector_type transposeTimes(const vector_type& other) const
-  {
-    return vector_type(m.transpose () * other.v);
-  }
-
-  inline T transposeDotX(const vector_type& other) const
-  {
-    return m.col(0).dot(other.v);
-  }
-
-  inline T transposeDotY(const vector_type& other) const
-  {
-    return m.col(1).dot(other.v);
-  }
-
-  inline T transposeDotZ(const vector_type& other) const
-  {
-    return m.col(2).dot(other.v);
-  }
-
-  inline T transposeDot(size_t i, const vector_type& other) const
-  {
-    return m.col (i).dot(other.v);
-  }
-
-  inline T dotX(const vector_type& other) const
-  {
-    return m.row (0).dot (other.v);
-  }
-
-  inline T dotY(const vector_type& other) const
-  {
-    return m.row (1).dot (other.v);
-  }
-
-  inline T dotZ(const vector_type& other) const
-  {
-    return m.row (2).dot (other.v);
-  }
-
-  inline T dot(size_t i, const vector_type& other) const
-  {
-    return m.row (i).dot (other.v);
-  }
-
-  inline void setValue(T xx, T xy, T xz,
-                       T yx, T yy, T yz,
-                       T zx, T zy, T zz)
-  {
-    m << xx, xy, xz,
-         yx, yy, yz,
-         zx, zy, zz;
-  }
-
-  inline void setValue(T x) { m.setConstant (x); }
-};
-
-
-template<typename T>
-eigen_wrapper_m3<T> abs(const eigen_wrapper_m3<T>& m)
-{
-  return eigen_wrapper_m3<T>(m.m.cwiseAbs ());
-}
-
-template<typename T>
-eigen_wrapper_m3<T> transpose(const eigen_wrapper_m3<T>& m)
-{
-  return eigen_wrapper_m3<T>(m.m.transpose ());
-}
-
-
-template<typename T>
-eigen_wrapper_m3<T> inverse(const eigen_wrapper_m3<T>& m)
-{
-  return eigen_wrapper_m3<T> (m.m.inverse().eval ());
-}
-
-template<typename T>
-struct eigen_m3 :
-  Eigen::Matrix <T, 3, 3>
-{
-  typedef T meta_type;
-  typedef eigen_v3<T> vector_type;
-  typedef Eigen::Matrix <T, 3, 3> Base;
-
-  typedef typename Base::ColXpr ColXpr;
-  typedef typename Base::ConstColXpr ConstColXpr;
-  typedef typename Base::RowXpr RowXpr;
-  typedef typename Base::ConstRowXpr ConstRowXpr;
-
-  eigen_m3(void): Base () { }
-
-  // This constructor allows you to construct MyVectorType from Eigen expressions
-  template<typename OtherDerived>
-    eigen_m3(const Eigen::MatrixBase<OtherDerived>& other)
-    : Base(other)
-  {}
-
-  // This method allows you to assign Eigen expressions to MyVectorType
-  template<typename OtherDerived>
-    eigen_m3& operator= (const Eigen::MatrixBase <OtherDerived>& other)
-    {
-      this->Base::operator=(other);
-      return *this;
-    }
-
-  eigen_m3(T xx, T xy, T xz,
-           T yx, T yy, T yz,
-           T zx, T zy, T zz)
-  {
-    setValue(xx, xy, xz,
-             yx, yy, yz,
-             zx, zy, zz);
-  }
-
-  eigen_m3(const vector_type& v1, const vector_type& v2, const vector_type& v3)
-  {
-    this->row(1) = v1;
-    this->row(2) = v2;
-    this->row(3) = v3;
-  }
-
-  inline ColXpr col(size_t i) { return this->Base::col (i); }
-  inline RowXpr row(size_t i) { return this->Base::row (i); }
-  inline ConstColXpr col(size_t i) const { return this->Base::col (i); }
-  inline ConstRowXpr row(size_t i) const { return this->Base::row (i); }
-
-  inline eigen_m3<T>& operator *= (const eigen_m3<T>& other) { return static_cast<eigen_m3<T>&>(this->operator*=(other)); }
-  inline eigen_m3<T>& operator += (const eigen_m3<T>& other) { return static_cast<eigen_m3<T>&>(this->operator+=(other)); }
-  inline eigen_m3<T>& operator -= (const eigen_m3<T>& other) { return static_cast<eigen_m3<T>&>(this->operator-=(other)); }
-
-  inline eigen_m3<T>& operator += (T c) { return static_cast<eigen_m3<T>&>(this->operator+=(c)); }
-  inline eigen_m3<T>& operator -= (T c) { return static_cast<eigen_m3<T>&>(this->operator-=(c)); }
-  inline eigen_m3<T>& operator *= (T c) { return static_cast<eigen_m3<T>&>(this->operator*=(c)); }
-  inline eigen_m3<T>& operator /= (T c) { return static_cast<eigen_m3<T>&>(this->operator/=(c)); }
-
-  static const eigen_m3<T>& getIdentity()
-  {
-    static const eigen_m3<T> I(Base::Identity ());
-    return I;
-  }
-
-  eigen_m3<T>& transpose() { this->transposeInPlace (); return *this; }
-
-  eigen_m3<T>& inverse()
-  {
-    this->Base::operator=(this->inverse ().eval());
-    // m = m.inverse().eval();
-    return *this;
-  }
-
-  template <typename OtherDerived>
-    const typename Eigen::ProductReturnType<eigen_m3<T>, OtherDerived>::Type
-    transposeTimes(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->Base::transpose() * other;
-  }
-
-  template <typename OtherDerived>
-    const typename Eigen::ProductReturnType<eigen_m3<T>, OtherDerived>::Type
-    timesTranspose(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->operator* (other.Base::transpose());
-  }
-
-  template <typename OtherDerived>
-  inline T transposeDotX(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->col(0).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T transposeDotY(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->col(1).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T transposeDotZ(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->col(2).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T transposeDot(size_t i, const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->col(i).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T dotX(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->row(0).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T dotY(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->row(1).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T dotZ(const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->row(2).dot(other);
-  }
-
-  template <typename OtherDerived>
-  inline T dot(size_t i, const Eigen::MatrixBase<OtherDerived>& other) const
-  {
-    return this->row(i).dot(other);
-  }
-
-  inline void setValue(T xx, T xy, T xz,
-                       T yx, T yy, T yz,
-                       T zx, T zy, T zz)
-  {
-    *this << xx, xy, xz,
-             yx, yy, yz,
-             zx, zy, zz;
-  }
-
-  inline void setValue(T x)
-  {
-    this->setConstant (x);
-  }
-};
-
-
-template<typename T>
-eigen_m3<T> abs(const eigen_m3<T>& m)
-{
-  return eigen_m3<T>(m.cwiseAbs ());
-}
-
-template<typename T>
-eigen_m3<T> transpose(const eigen_m3<T>& m)
-{
-  return eigen_m3<T>(m.eigen_m3<T>::Base::transpose ());
-}
-
-
-template<typename T>
-eigen_m3<T> inverse(const eigen_m3<T>& m)
-{
-  return eigen_m3<T> (m.eigen_m3<T>::Base::inverse().eval ());
-}
-
-}
-
-}
-
-#endif
diff --git a/include/hpp/fcl/eigen/plugins/ccd/interval-matrix.h b/include/hpp/fcl/eigen/plugins/ccd/interval-matrix.h
deleted file mode 100644
index e69de29b..00000000
diff --git a/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h b/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
deleted file mode 100644
index 9ec6217f..00000000
--- a/include/hpp/fcl/eigen/plugins/ccd/interval-vector.h
+++ /dev/null
@@ -1,7 +0,0 @@
-template <typename Derived>
-IVector3& operator=(const Eigen::MatrixBase<Derived>& other)
-{
-  const Vec3f& tmp (other);
-  setValue (tmp);
-  return *this;
-}
diff --git a/include/hpp/fcl/eigen/product.h b/include/hpp/fcl/eigen/product.h
deleted file mode 100644
index 3998cf39..00000000
--- a/include/hpp/fcl/eigen/product.h
+++ /dev/null
@@ -1,39 +0,0 @@
-namespace internal {
-
-template<typename Derived, typename OtherDerived, bool coefwise> struct deduce_fcl_type {};
-
-template<typename Derived, typename OtherDerived>
-struct deduce_fcl_type<Derived, OtherDerived, false> {
-  typedef typename ProductReturnType<Derived, OtherDerived>::Type Type;
-};
-template<typename Derived, typename OtherDerived>
-struct deduce_fcl_type<Derived, OtherDerived, true> {
-  typedef CwiseBinaryOp<scalar_multiple_op<typename Derived::Scalar>, const Derived, const OtherDerived> Type;
-};
-
-}
-
-template<typename Derived, typename OtherDerived>
-struct FclProduct
-{
-  enum {
-    COEFWISE = Derived::ColsAtCompileTime == 1 && OtherDerived::ColsAtCompileTime == 1
-  };
-
-  typedef typename internal::remove_fcl<Derived>::type EDerived;
-  typedef typename internal::remove_fcl<OtherDerived>::type EOtherDerived;
-
-  typedef FclOp<typename internal::deduce_fcl_type<EDerived, EOtherDerived, COEFWISE>::Type> ProductType;
-  typedef FclOp<typename ProductReturnType<Transpose<Derived>, EOtherDerived >::Type> TransposeTimesType;
-  typedef FclOp<typename ProductReturnType<EDerived, Transpose<EOtherDerived> >::Type> TimesTransposeType;
-  typedef FclOp<typename ProductReturnType<ProductType, Transpose<EDerived>  >::Type> TensorTransformType;
-  static EIGEN_STRONG_INLINE ProductType run (const Derived& l, const OtherDerived& r) { return ProductType (l, r); }
-};
-
-#define FCL_EIGEN_MAKE_PRODUCT_OPERATOR() \
-      template <typename OtherDerived> \
-      EIGEN_STRONG_INLINE const typename FclProduct<const typename FCL_EIGEN_CURRENT_CLASS::Base, const OtherDerived>::ProductType \
-      operator*(const MatrixBase<OtherDerived>& other) const \
-      { \
-        return FclProduct<const typename FCL_EIGEN_CURRENT_CLASS::Base, const OtherDerived>::run (*this, other.derived()); \
-      }
diff --git a/include/hpp/fcl/eigen/taylor_operator.h b/include/hpp/fcl/eigen/taylor_operator.h
deleted file mode 100644
index 1de50b31..00000000
--- a/include/hpp/fcl/eigen/taylor_operator.h
+++ /dev/null
@@ -1,25 +0,0 @@
-#ifndef FCL_CCD_TAYLOR_OPERATOR_H
-#define FCL_CCD_TAYLOR_OPERATOR_H
-
-#include <hpp/fcl/math/vec_3f.h>
-#include <hpp/fcl/math/matrix_3f.h>
-
-namespace fcl {
-
-class TVector3;
-class TMatrix3;
-
-template<int Col> struct TaylorReturnType {};
-template<> struct TaylorReturnType<1> { typedef TVector3 type; typedef Vec3f    eigen_type; };
-template<> struct TaylorReturnType<3> { typedef TMatrix3 type; typedef Matrix3f eigen_type; };
-
-template<typename Derived>
-typename TaylorReturnType<Derived::ColsAtCompileTime>::type operator * (const Eigen::MatrixBase<Derived>& v, const TaylorModel& a)
-{
-  const typename TaylorReturnType<Derived::ColsAtCompileTime>::eigen_type b = v.derived();
-  return b * a;
-}
-
-}
-
-#endif // FCL_CCD_TAYLOR_OPERATOR_H
diff --git a/include/hpp/fcl/eigen/vec_3fx.h b/include/hpp/fcl/eigen/vec_3fx.h
deleted file mode 100644
index 6eef9260..00000000
--- a/include/hpp/fcl/eigen/vec_3fx.h
+++ /dev/null
@@ -1,770 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Joseph Mirabel */
-
-#ifndef FCL_EIGEN_VEC_3F_H
-#define FCL_EIGEN_VEC_3F_H
-
-#include <hpp/fcl/config-fcl.hh>
-#include <hpp/fcl/data_types.h>
-
-#include <Eigen/Dense>
-#include <Eigen/Geometry>
-
-#include <cmath>
-#include <iostream>
-#include <limits>
-
-#define FCL_CCD_INTERVALVECTOR_PLUGIN <hpp/fcl/eigen/plugins/ccd/interval-vector.h>
-#define FCL_CCD_MATRIXVECTOR_PLUGIN <hpp/fcl/eigen/plugins/ccd/interval-matrix.h>
-
-#define FCL_EIGEN_EXPOSE_PARENT_TYPE(Type) typedef typename Base::Type Type;
-
-#define FCL_EIGEN_MAKE_CWISE_BINARY_OP(METHOD,FUNCTOR) \
-      template <typename OtherDerived> \
-      EIGEN_STRONG_INLINE const FclOp<const CwiseBinaryOp<FUNCTOR<Scalar>, const typename FCL_EIGEN_CURRENT_CLASS::Base, const OtherDerived> > \
-      (METHOD) (const MatrixBase<OtherDerived>& other) const \
-      { \
-        return FclOp <const CwiseBinaryOp<FUNCTOR<Scalar>, const typename FCL_EIGEN_CURRENT_CLASS::Base, const OtherDerived> > (*this, other.derived()); \
-      }
-
-#define FCL_EIGEN_MAKE_CWISE_UNARY_OP(METHOD,FUNCTOR) \
-      EIGEN_STRONG_INLINE const FclOp<const CwiseUnaryOp<FUNCTOR<Scalar>, const typename FCL_EIGEN_CURRENT_CLASS::Base> > \
-      (METHOD) (const Scalar& scalar) const \
-      { \
-        return FclOp <const CwiseUnaryOp<FUNCTOR<Scalar>, const typename FCL_EIGEN_CURRENT_CLASS::Base> > (*this, FUNCTOR<Scalar>(scalar)); \
-      }
-
-#define FCL_EIGEN_RENAME_PARENT_METHOD(OLD,NEW,RETTYPE) \
-      template <typename OtherDerived> \
-      EIGEN_STRONG_INLINE RETTYPE (METHOD) () \
-      { \
-        return (this->Base::METHOD) (); \
-      }
-
-#define FCL_EIGEN_MAKE_EXPOSE_PARENT1(METHOD) \
-      template <typename OtherDerived> \
-      EIGEN_STRONG_INLINE FclMatrix& (METHOD) (const MatrixBase<OtherDerived>& other) \
-      { \
-        (this->Base::METHOD)(other); return *this; \
-      }
-
-#define FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY1(METHOD) \
-      template <typename OtherDerived> \
-      EIGEN_STRONG_INLINE FclMatrix& (METHOD) (const MatrixBase<OtherDerived>& other) \
-      { \
-        (this->array().METHOD)(other.derived().array()); return *this; \
-      }
-
-#define FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY_SCALAR1(METHOD) \
-      EIGEN_STRONG_INLINE FCL_EIGEN_CURRENT_CLASS& (METHOD) (const Scalar& other) \
-      { \
-        (this->array().METHOD)(other); return *this; \
-      }
-
-#define FCL_EIGEN_MAKE_GET_COL_ROW() \
-  EIGEN_STRONG_INLINE FclOp<ColXpr> getColumn (size_t i) { return FclOp<ColXpr>(*this, i); } \
-  EIGEN_STRONG_INLINE FclOp<RowXpr> getRow    (size_t i) { return FclOp<RowXpr>(*this, i); } \
-  EIGEN_STRONG_INLINE FclOp<ConstColXpr> getColumn (size_t i) const { return FclOp<ConstColXpr>(*this, i); } \
-  EIGEN_STRONG_INLINE FclOp<ConstRowXpr> getRow    (size_t i) const { return FclOp<ConstRowXpr>(*this, i); }
-
-#define FCL_EIGEN_MATRIX_DOT_AXIS(NAME,axis,index) \
-  template<typename OtherDerived> \
-  EIGEN_STRONG_INLINE Scalar NAME##axis (const MatrixBase<OtherDerived>& other) const \
-  { return this->NAME (index, other); }
-
-#define FCL_EIGEN_MATRIX_DOT(NAME,FUNC) \
-  template<typename OtherDerived> \
-  EIGEN_STRONG_INLINE Scalar NAME(size_t i, const MatrixBase<OtherDerived>& other) const \
-  { \
-    EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(FCL_EIGEN_CURRENT_CLASS, 3, 3); \
-    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived, 3); \
-    return this->FUNC(i).dot(other); \
-  } \
-  FCL_EIGEN_MATRIX_DOT_AXIS(NAME,X,0)\
-  FCL_EIGEN_MATRIX_DOT_AXIS(NAME,Y,1)\
-  FCL_EIGEN_MATRIX_DOT_AXIS(NAME,Z,2)
-
-#define FCL_EIGEN_MAKE_CROSS() \
-  template<typename OtherDerived> \
-  EIGEN_STRONG_INLINE typename BinaryReturnType<FCL_EIGEN_CURRENT_CLASS::Base,OtherDerived>::Cross \
-  cross (const MatrixBase<OtherDerived>& other) const { return this->Base::cross (other); }
-
-#define FCL_EIGEN_MAKE_DOT() \
-  template <typename OtherDerived> \
-  EIGEN_STRONG_INLINE Scalar dot (const MatrixBase<OtherDerived>& other) const \
-  { return this->Base::dot (other.derived()); }
-
-namespace fcl {
-template <typename Derived>
-class FclType
-{
-  public:
-    Derived& fcl () { return static_cast<Derived&> (*this); }
-    const Derived& fcl () const { return static_cast<const Derived&> (*this); }
-};
-}
-
-namespace Eigen {
-  template <typename T> class FclOp;
-  template <typename T, int Cols, int Options> class FclMatrix;
-
-  namespace internal {
-
-    template<typename T> struct traits< FclOp<T> > : traits <T> {};
-    template<typename T, int Cols, int _Options>
-      struct traits< FclMatrix<T, Cols, _Options> >
-      : traits<typename FclMatrix<T, Cols, _Options>::Base>
-      {};
-
-    template <typename Derived> struct remove_fcl { typedef Derived type; };
-    template <typename Derived> struct remove_fcl <FclOp<Derived> > { typedef Derived type; };
-    template <typename Derived> struct remove_fcl <const FclOp<Derived> > { typedef Derived type; };
-    template <typename T, int Col, int Options> struct remove_fcl <FclMatrix<T,Col,Options> > { typedef typename FclMatrix<T,Col,Options>::Base type; };
-    template <typename T, int Col, int Options> struct remove_fcl <const FclMatrix<T,Col,Options> > { typedef typename FclMatrix<T,Col,Options>::Base type; };
-  }
-
-#include <hpp/fcl/eigen/product.h>
-
-  template <typename Derived>
-    struct UnaryReturnType {
-      typedef typename Derived::Scalar Scalar;
-      typedef typename Derived::PlainObject Normalize;
-      typedef FclOp <
-        const CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const Derived>
-        > Opposite;
-      typedef FclOp <
-        const CwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived>
-        > Abs;
-    };
-
-  template <typename Derived, typename OtherDerived>
-    struct BinaryReturnType {
-      typedef typename Derived::Scalar Scalar;
-      typedef FclOp <
-        const CwiseBinaryOp<internal::scalar_difference_op<Scalar>,
-              const Derived, const OtherDerived>
-                > Difference;
-      // static inline const Difference difference (const Derived& l, const OtherDerived& r)
-      // { return Difference (l, r, internal::scalar_difference_op<Scalar>()); }
-      typedef FclOp <
-        const CwiseBinaryOp<internal::scalar_sum_op<Scalar>,
-              const Derived, const OtherDerived>
-                > Sum;
-      typedef FclOp <
-        const CwiseBinaryOp<internal::scalar_min_op<Scalar>,
-              const Derived, const OtherDerived>
-                > Min;
-      typedef FclOp <
-        const CwiseBinaryOp<internal::scalar_max_op<Scalar>,
-              const Derived, const OtherDerived>
-                > Max;
-      typedef FclMatrix <Scalar, 1, 0> Cross;
-    };
-
-#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 = internal::traits<Matrix <T, 3, Cols> >::Options >
-class FclMatrix : public Matrix <T, 3, Cols, _Options>, public ::fcl::FclType<FclMatrix <T, Cols, _Options> >
-{
-public:
-  typedef Matrix <T, 3, Cols, _Options> Base;
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(Scalar)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ColXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(RowXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ConstColXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ConstRowXpr)
-
-  // Compatibility with other Matrix3fX and Vec3f
-  typedef T U;
-  typedef T meta_type;
-
-  FclMatrix(void): Base(Base::Zero()) {}
-
-  // This constructor allows you to construct MyVectorType from Eigen expressions
-  template<typename OtherDerived>
-    FclMatrix(const MatrixBase<OtherDerived>& other)
-    : Base(other)
-    {}
-
-  // This method allows you to assign Eigen expressions to MyVectorType
-  template<typename OtherDerived>
-    FclMatrix& operator=(const MatrixBase <OtherDerived>& other)
-    {
-      this->Base::operator=(other);
-      return *this;
-    }
-
-  /// @brief create Vector (x, y, z)
-  FclMatrix(T x, T y, T z) : Base(x, y, z) {}
-
-  FclMatrix(T xx, T xy, T xz,
-            T yx, T yy, T yz,
-            T zx, T zy, T zz) : Base()
-  {
-    *this << xx, xy, xz, yx, yy, yz, zx, zy, zz;
-  }
-
-  template <typename Vector>
-  FclMatrix(const ::fcl::FclType<Vector>& r0,
-            const ::fcl::FclType<Vector>& r1,
-            const ::fcl::FclType<Vector>& r2) : Base()
-  {
-    this->row(0) = r0.fcl();
-    this->row(1) = r1.fcl();
-    this->row(2) = r2.fcl();
-  }
-
-  /// @brief create vector (x, x, x)
-  FclMatrix(T x) : Base(Base::Constant (x)) {}
-
-  /// @brief create vector using the internal data type
-  // Vec3fX(const T& data_) : data(data_) {}
-
-  // inline U operator [] (size_t i) const { return data[i]; }
-  // inline U& operator [] (size_t i) { return data[i]; }
-
-  // FclOp<typename Base::ColXpr> getColumn (size_t i) { return FclOp<typename Base::ColXpr>(*this, i); }
-  // FclOp<typename Base::RowXpr> getRow    (size_t i) { return FclOp<typename Base::RowXpr>(*this, i); }
-  // FclOp<typename Base::ColXpr> getColumn (size_t i) { return FclOp<typename Base::ColXpr>(*this, i); }
-  // FclOp<typename Base::RowXpr> getRow    (size_t i) { return FclOp<typename Base::RowXpr>(*this, i); }
-  FCL_EIGEN_MAKE_GET_COL_ROW()
-  FCL_EIGEN_MATRIX_DOT(dot,row)
-  FCL_EIGEN_MATRIX_DOT(transposeDot,col)
-
-  FCL_EIGEN_MAKE_DOT()
-
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator+,internal::scalar_sum_op)
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator-,internal::scalar_difference_op)
-  // Map this to scalar product or matrix product depending on the Cols.
-  // FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator*,internal::scalar_product_op)
-  FCL_EIGEN_MAKE_PRODUCT_OPERATOR()
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator/,internal::scalar_quotient_op)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT1(operator+=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT1(operator-=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY1(operator*=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY1(operator/=)
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator+,internal::scalar_add_op)
-  // This operator cannot be implement with the macro
-  // FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator-,internal::scalar_difference_op)
-  EIGEN_STRONG_INLINE const FclOp<const CwiseUnaryOp<internal::scalar_add_op<Scalar>, const Base> >
-  operator- (const Scalar& scalar) const
-  {
-    return FclOp <const CwiseUnaryOp<internal::scalar_add_op<Scalar>, const Base> > (*this, internal::scalar_add_op<Scalar>(-scalar));
-  }
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator*,internal::scalar_multiple_op)
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator/,internal::scalar_quotient1_op)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY_SCALAR1(operator+=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY_SCALAR1(operator-=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY_SCALAR1(operator*=)
-  FCL_EIGEN_MAKE_EXPOSE_PARENT_ARRAY_SCALAR1(operator/=)
-  inline const typename UnaryReturnType<Base>::Opposite operator-() const { return typename UnaryReturnType<Base>::Opposite(*this); }
-  // There is no class for cross 
-  // inline Vec3fX cross(const Vec3fX& other) const { return Vec3fX(details::cross_prod(data, other.data)); }
-  FCL_EIGEN_MAKE_CROSS()
-  inline FclMatrix& normalize()
-  {
-    T sqr_length = this->squaredNorm();
-    if(sqr_length > 0) this->operator/= ((T)std::sqrt(sqr_length));
-    return *this;
-  }
-
-  inline FclMatrix& abs() 
-  {
-    *this = this->cwiseAbs ();
-    return *this;
-  }
-
-  inline bool equal(const FclMatrix& other, T epsilon = std::numeric_limits<T>::epsilon() * 100) const
-  {
-    return ((*this - other).cwiseAbs().array () < epsilon).all();
-  }
-
-  bool operator == (const FclMatrix& other) const
-  {
-    return equal(other, 0);
-  }
-
-  bool operator != (const FclMatrix& other) const
-  {
-    return !(*this == other);
-  }
-
-  inline FclMatrix& ubound(const FclMatrix& u)
-  {
-    *this = this->cwiseMin (u);
-    return *this;
-  }
-
-  inline FclMatrix& lbound(const FclMatrix& l)
-  {
-    *this = this->cwiseMax (l);
-    return *this;
-  }
-
-  bool isZero() const
-  {
-    return (this->m_storage.data()[0] == 0)
-      &&   (this->m_storage.data()[1] == 0)
-      &&   (this->m_storage.data()[2] == 0);
-  }
-
-  FclMatrix& transpose () {
-    EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Base, 3, 3);
-    this->transposeInPlace();
-    return *this;
-  }
-
-  FclMatrix& inverse()
-  {
-    this->Base::operator=(this->Base::inverse ().eval());
-    return *this;
-  }
-
-  template<typename OtherDerived>
-  EIGEN_STRONG_INLINE const typename FclProduct<const Base,const OtherDerived>::TransposeTimesType
-  transposeTimes (const MatrixBase<OtherDerived>& other) const
-  {
-    const Transpose<const Base> t (*this);
-    return typename FclProduct<const Base,const OtherDerived>::TransposeTimesType (t, other.derived());
-  }
-
-  template<typename OtherDerived>
-  EIGEN_STRONG_INLINE const typename FclProduct<const Base,const OtherDerived>::TimesTransposeType
-  timesTranspose (const MatrixBase<OtherDerived>& other) const
-  {
-    const Transpose<const OtherDerived> t (other.derived());
-    return typename FclProduct<const Base,const OtherDerived>::TimesTransposeType (*this, t);
-  }
-
-  template<typename OtherDerived>
-  EIGEN_STRONG_INLINE const typename FclProduct<const Base,const OtherDerived>::TensorTransformType
-  tensorTransform(const MatrixBase<OtherDerived>& other) const
-  {
-    const Transpose<const Base> t (*this);
-    const typename FclProduct<const Base,const OtherDerived>::ProductType left (*this, other.derived());
-    return typename FclProduct<const Base,const OtherDerived>::TensorTransformType (left, t);
-  }
-
-  static const FclMatrix& getIdentity()
-  {
-    static const FclMatrix I((T)1, (T)0, (T)0,
-                             (T)0, (T)1, (T)0,
-                             (T)0, (T)0, (T)1);
-    return I;
-  }
-
-  /// @brief Set the matrix from euler angles YPR around ZYX axes
-  /// @param eulerX Roll about X axis
-  /// @param eulerY Pitch around Y axis
-  /// @param eulerZ Yaw aboud Z axis
-  ///  
-  /// These angles are used to produce a rotation matrix. The euler
-  /// angles are applied in ZYX order. I.e a vector is first rotated 
-  /// about X then Y and then Z
-  inline void setEulerZYX(Scalar eulerX, Scalar eulerY, Scalar eulerZ)
-  {
-    EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(FclMatrix, 3, 3);
-    Scalar ci(std::cos(eulerX));
-    Scalar cj(std::cos(eulerY));
-    Scalar ch(std::cos(eulerZ));
-    Scalar si(std::sin(eulerX));
-    Scalar sj(std::sin(eulerY));
-    Scalar sh(std::sin(eulerZ));
-    Scalar cc = ci * ch;
-    Scalar cs = ci * sh;
-    Scalar sc = si * ch;
-    Scalar ss = si * sh;
-
-    *this << cj * ch, sj * sc - cs, sj * cc + ss,
-             cj * sh, sj * ss + cc, sj * cs - sc, 
-             -sj,     cj * si,      cj * ci;
-
-  }
-
-  /// @brief Set the matrix from euler angles using YPR around YXZ respectively
-  /// @param yaw Yaw about Y axis
-  /// @param pitch Pitch about X axis
-  /// @param roll Roll about Z axis 
-  void setEulerYPR(Scalar yaw, Scalar pitch, Scalar roll)
-  {
-    setEulerZYX(roll, pitch, yaw);
-  }
-};
-
-#undef FCL_EIGEN_CURRENT_CLASS
-#define FCL_EIGEN_CURRENT_CLASS FclOp
-
-template <typename EigenOp>
-class FclOp : public EigenOp, public ::fcl::FclType<FclOp <EigenOp> >
-{
-public:
-  typedef typename internal::traits<EigenOp>::Scalar T;
-  typedef EigenOp Base;
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(Scalar)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ColXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(RowXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ConstColXpr)
-  FCL_EIGEN_EXPOSE_PARENT_TYPE(ConstRowXpr)
-
-  // template<typename Lhs, typename Rhs, typename BinaryOp>
-  // FclOp (const Lhs& lhs, const Rhs& rhs, const BinaryOp& bop)
-    // : Base (lhs, rhs, bop) {}
-
-  template<typename Lhs, typename Rhs>
-  FclOp (Lhs& lhs, const Rhs& rhs)
-    : Base (lhs, rhs) {}
-
-  template<typename OtherEigenOp>
-  FclOp (const FclOp<OtherEigenOp>& other)
-    : Base (other) {}
-
-  template<typename XprType>
-  FclOp (XprType& xpr)
-    : Base (xpr) {}
-
-  FCL_EIGEN_MAKE_GET_COL_ROW()
-  FCL_EIGEN_MATRIX_DOT(dot,row)
-  FCL_EIGEN_MATRIX_DOT(transposeDot,col)
-
-  FCL_EIGEN_MAKE_DOT()
-
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator+,internal::scalar_sum_op)
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator-,internal::scalar_difference_op)
-  // Map this to scalar product or matrix product depending on the Cols.
-  // FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator*,internal::scalar_product_op)
-  FCL_EIGEN_MAKE_PRODUCT_OPERATOR()
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(operator/,internal::scalar_quotient_op)
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator+,internal::scalar_add_op)
-  // This operator cannot be implement with the macro
-  // FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator-,internal::scalar_difference_op)
-  EIGEN_STRONG_INLINE const FclOp<const CwiseUnaryOp<internal::scalar_add_op<Scalar>, const Base> >
-  operator- (const Scalar& scalar) const
-  {
-    return FclOp <const CwiseUnaryOp<internal::scalar_add_op<Scalar>, const Base> > (*this, internal::scalar_add_op<Scalar>(-scalar));
-  }
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator*,internal::scalar_multiple_op)
-  FCL_EIGEN_MAKE_CWISE_UNARY_OP(operator/,internal::scalar_quotient1_op)
-  inline const typename UnaryReturnType<const Base>::Opposite operator-() const { return typename UnaryReturnType<const Base>::Opposite(*this); }
-
-  FCL_EIGEN_MAKE_CROSS()
-
-  inline const typename UnaryReturnType<EigenOp>::Normalize
-    normalize() const
-  {
-    return this->normalized ();
-    // T sqr_length = this->squaredNorm();
-    // if(sqr_length > 0) CwiseExpose (*this /= ((T)sqrt(sqr_length)));
-    // return *this;
-  }
-
-  /*
-  inline Vec3fX<T> normalize(bool* signal)
-  {
-    T sqr_length = this->squaredNorm();
-    if(sqr_length > 0)
-    {
-      *this /= ((T)sqrt(sqr_length));
-      *signal = true;
-    }
-    else
-      *signal = false;
-    return *this;
-  }
-  // */
-
-  inline const typename UnaryReturnType<EigenOp>::Abs
-    abs() const
-  {
-    return typename UnaryReturnType<EigenOp>::Abs (*this);
-  }
-
-  template <typename Derived>
-  inline bool equal(const Eigen::MatrixBase<Derived>& other, T epsilon = std::numeric_limits<T>::epsilon() * 100) const
-  {
-    return ((*this - other).cwiseAbs().array () < epsilon).all();
-  }
-
-  template <typename Derived>
-  bool operator == (const Eigen::MatrixBase<Derived>& other) const
-  {
-    return equal(other, 0);
-  }
-
-  template <typename Derived>
-  bool operator != (const Eigen::MatrixBase<Derived>& other) const
-  {
-    return !(*this == other);
-  }
-
-  // Not in place.
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(ubound,internal::scalar_min_op)
-  FCL_EIGEN_MAKE_CWISE_BINARY_OP(lbound,internal::scalar_max_op)
-
-  bool isZero() const
-  {
-    return this->Base::isZero ();
-  }
-
-  const FclOp<Transpose<const Base> > transpose () const {
-    EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(EigenOp, 3, 3);
-    return FclOp<Transpose<const Base> >(*this);
-  }
-
-  // const FclOp<internal::inverse_impl<FclOp> > inverse () const { return FclOp<Transpose<FclOp> >(*this); }
-};
-
-}
-
-namespace fcl
-{
-// #if 0
-template<typename T, int _Options>
-static inline Eigen::FclMatrix<T, 1, _Options> normalize(const Eigen::FclMatrix<T, 1, _Options>& v)
-{
-  T sqr_length = v.squaredNorm ();
-  if(sqr_length > 0)
-    return v / (T)sqrt(sqr_length);
-  else
-    return v;
-}
-
-template<typename Derived>
-static inline typename Derived::Scalar triple(
-    const FclType<Derived>& x,
-    const FclType<Derived>& y,
-    const FclType<Derived>& z)
-{
-  return x.fcl().dot(y.fcl().cross(z.fcl()));
-}
-
-
-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.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.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.fcl());
-}
-
-template<typename Derived>
-void generateCoordinateSystem(
-    FclType<Derived>& _w,
-    FclType<Derived>& _u,
-    FclType<Derived>& _v)
-{
-  typedef typename Derived::Scalar T;
-
-  Derived& w = _w.fcl();
-  Derived& u = _u.fcl();
-  Derived& v = _v.fcl();
-
-  T inv_length;
-  if(std::abs(w[0]) >= std::abs(w[1]))
-  {
-    inv_length = (T)1.0 / sqrt(w[0] * w[0] + w[2] * w[2]);
-    u[0] = -w[2] * inv_length;
-    u[1] = (T)0;
-    u[2] = w[0] * inv_length;
-    v[0] = w[1] * u[2];
-    v[1] = w[2] * u[0] - w[0] * u[2];
-    v[2] = -w[1] * u[0];
-  }
-  else
-  {
-    inv_length = (T)1.0 / sqrt(w[1] * w[1] + w[2] * w[2]);
-    u[0] = (T)0;
-    u[1] = w[2] * inv_length;
-    u[2] = -w[1] * inv_length;
-    v[0] = w[1] * u[2] - w[2] * u[1];
-    v[1] = -w[0] * u[2];
-    v[2] = w[0] * u[1];
-  }
-}
-
- // template <typename T>
-   // inline Vec3fX <T> operator * (const typename Vec3fX <T>::U& t,
-				 // const Vec3fX <T>& v)
-   // {
-     // return Vec3fX <T> (v.data * t);
-   // }
-
-// #endif
-
-/* ----- Start Matrices ------ */
-template<typename Matrix, typename Vector>
-void hat(Matrix& mat, const Vector& vec)
-{
-  mat << 0, -vec[2], vec[1], vec[2], 0, -vec[0], -vec[1], vec[0], 0;
-}
-
-template<typename Matrix, typename Vector>
-void relativeTransform(const Matrix& R1, const Vector& t1,
-                       const Matrix& R2, const Vector& t2,
-                       Matrix& R, Vector& t)
-{
-  R = R1.transposeTimes(R2);
-  t = R1.transposeTimes(t2 - t1);
-}
-
-/// @brief compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors
-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.fcl());
-  int n = 3;
-  int j, iq, ip, i;
-  Scalar tresh, theta, tau, t, sm, s, h, g, c;
-  int nrot;
-  Scalar b[3];
-  Scalar z[3];
-  Scalar v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
-  Scalar d[3];
-
-  for(ip = 0; ip < n; ++ip)
-  {
-    b[ip] = d[ip] = R(ip, ip);
-    z[ip] = 0;
-  }
-
-  nrot = 0;
-
-  for(i = 0; i < 50; ++i)
-  {
-    sm = 0;
-    for(ip = 0; ip < n; ++ip)
-      for(iq = ip + 1; iq < n; ++iq)
-        sm += std::abs(R(ip, iq));
-    if(sm == 0.0)
-    {
-      vout[0] << v[0][0], v[0][1], v[0][2];
-      vout[1] << v[1][0], v[1][1], v[1][2];
-      vout[2] << v[2][0], v[2][1], v[2][2];
-      dout[0] = d[0]; dout[1] = d[1]; dout[2] = d[2];
-      return;
-    }
-
-    if(i < 3) tresh = 0.2 * sm / (n * n);
-    else tresh = 0.0;
-
-    for(ip = 0; ip < n; ++ip)
-    {
-      for(iq= ip + 1; iq < n; ++iq)
-      {
-        g = 100.0 * std::abs(R(ip, iq));
-        if(i > 3 &&
-           std::abs(d[ip]) + g == std::abs(d[ip]) &&
-           std::abs(d[iq]) + g == std::abs(d[iq]))
-          R(ip, iq) = 0.0;
-        else if(std::abs(R(ip, iq)) > tresh)
-        {
-          h = d[iq] - d[ip];
-          if(std::abs(h) + g == std::abs(h)) t = (R(ip, iq)) / h;
-          else
-          {
-            theta = 0.5 * h / (R(ip, iq));
-            t = 1.0 /(std::abs(theta) + std::sqrt(1.0 + theta * theta));
-            if(theta < 0.0) t = -t;
-          }
-          c = 1.0 / std::sqrt(1 + t * t);
-          s = t * c;
-          tau = s / (1.0 + c);
-          h = t * R(ip, iq);
-          z[ip] -= h;
-          z[iq] += h;
-          d[ip] -= h;
-          d[iq] += h;
-          R(ip, iq) = 0.0;
-          for(j = 0; j < ip; ++j) { g = R(j, ip); h = R(j, iq); R(j, ip) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
-          for(j = ip + 1; j < iq; ++j) { g = R(ip, j); h = R(j, iq); R(ip, j) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
-          for(j = iq + 1; j < n; ++j) { g = R(ip, j); h = R(iq, j); R(ip, j) = g - s * (h + g * tau); R(iq, j) = h + s * (g - h * tau); }
-          for(j = 0; j < n; ++j) { g = v[j][ip]; h = v[j][iq]; v[j][ip] = g - s * (h + g * tau); v[j][iq] = h + s * (g - h * tau); }
-          nrot++;
-        }
-      }
-    }
-    for(ip = 0; ip < n; ++ip)
-    {
-      b[ip] += z[ip];
-      d[ip] = b[ip];
-      z[ip] = 0.0;
-    }
-  }
-
-  std::cerr << "eigen: too many iterations in Jacobi transform." << std::endl;
-
-  return;
-}
-
-template<typename Derived>
-Eigen::FclOp<Eigen::Transpose<const typename Eigen::internal::remove_fcl<Derived>::type> > transpose(const FclType<Derived>& R)
-{
-  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, 3, 3);
-  return Eigen::FclOp<Eigen::Transpose<const typename Eigen::internal::remove_fcl<Derived>::type > > (R.fcl());
-}
-
-template<typename T, int _Options>
-Eigen::FclMatrix<T,3,_Options> inverse(const Eigen::FclMatrix<T, 3, _Options>& R)
-{
-  return R.inverse();
-}
-
-template<typename Matrix, typename Vector>
-typename Matrix::Scalar quadraticForm(const Matrix& R, const Vector& v)
-{
-  return v.dot(R * v);
-}
-
-
-}
-
-
-#endif
diff --git a/include/hpp/fcl/math/math_details.h b/include/hpp/fcl/math/math_details.h
deleted file mode 100644
index 50586708..00000000
--- a/include/hpp/fcl/math/math_details.h
+++ /dev/null
@@ -1,501 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef FCL_MATH_DETAILS_H
-#define FCL_MATH_DETAILS_H
-
-#if FCL_HAVE_EIGEN
-# error "This file should not be included when compiling with Eigen library"
-#endif
-
-#include <cmath>
-#include <algorithm>
-#include <cstring>
-
-namespace fcl
-{
-
-namespace details
-{
-
-
-template <typename T>
-struct Vec3Data
-{
-  typedef T meta_type;
-
-  T vs[3];
-  Vec3Data() { setValue(0); }
-  Vec3Data(T x)
-  {
-    setValue(x);
-  }
-
-  Vec3Data(T* x)
-  {
-    memcpy(vs, x, sizeof(T) * 3);
-  }
-
-  Vec3Data(T x, T y, T z)
-  {
-    setValue(x, y, z);
-  }
-
-  inline void setValue(T x, T y, T z)
-  {
-    vs[0] = x; vs[1] = y; vs[2] = z;
-  }
-
-  inline void setValue(T x)
-  {
-    vs[0] = x; vs[1] = x; vs[2] = x;
-  }
-
-  inline Vec3Data<T>& ubound(const Vec3Data<T>& u) 
-  {
-    vs[0] = std::min(vs[0], u.vs[0]);
-    vs[1] = std::min(vs[1], u.vs[1]);
-    vs[2] = std::min(vs[2], u.vs[2]);
-    return *this;
-  }
-
-  inline Vec3Data<T>& lbound(const Vec3Data<T>& l)
-  {
-    vs[0] = std::max(vs[0], l.vs[0]);
-    vs[1] = std::max(vs[1], l.vs[1]);
-    vs[2] = std::max(vs[2], l.vs[2]);
-    return *this;
-  }
-
-  T operator [] (size_t i) const { return vs[i]; }
-  T& operator [] (size_t i) { return vs[i]; }
-
-  inline Vec3Data<T> operator + (const Vec3Data<T>& other) const { return Vec3Data<T>(vs[0] + other.vs[0], vs[1] + other.vs[1], vs[2] + other.vs[2]); }
-  inline Vec3Data<T> operator - (const Vec3Data<T>& other) const { return Vec3Data<T>(vs[0] - other.vs[0], vs[1] - other.vs[1], vs[2] - other.vs[2]); }
-  inline Vec3Data<T> operator * (const Vec3Data<T>& other) const { return Vec3Data<T>(vs[0] * other.vs[0], vs[1] * other.vs[1], vs[2] * other.vs[2]); }
-  inline Vec3Data<T> operator / (const Vec3Data<T>& other) const { return Vec3Data<T>(vs[0] / other.vs[0], vs[1] / other.vs[1], vs[2] / other.vs[2]); }
-  inline Vec3Data<T>& operator += (const Vec3Data<T>& other) { vs[0] += other.vs[0]; vs[1] += other.vs[1]; vs[2] += other.vs[2]; return *this; }
-  inline Vec3Data<T>& operator -= (const Vec3Data<T>& other) { vs[0] -= other.vs[0]; vs[1] -= other.vs[1]; vs[2] -= other.vs[2]; return *this; }
-  inline Vec3Data<T>& operator *= (const Vec3Data<T>& other) { vs[0] *= other.vs[0]; vs[1] *= other.vs[1]; vs[2] *= other.vs[2]; return *this; }
-  inline Vec3Data<T>& operator /= (const Vec3Data<T>& other) { vs[0] /= other.vs[0]; vs[1] /= other.vs[1]; vs[2] /= other.vs[2]; return *this; }
-  inline Vec3Data<T> operator + (T t) const { return Vec3Data<T>(vs[0] + t, vs[1] + t, vs[2] + t); }
-  inline Vec3Data<T> operator - (T t) const { return Vec3Data<T>(vs[0] - t, vs[1] - t, vs[2] - t); }
-  inline Vec3Data<T> operator * (T t) const { return Vec3Data<T>(vs[0] * t, vs[1] * t, vs[2] * t); }
-  inline Vec3Data<T> operator / (T t) const { T inv_t = 1.0 / t; return Vec3Data<T>(vs[0] * inv_t, vs[1] * inv_t, vs[2] * inv_t); }
-  inline Vec3Data<T>& operator += (T t) { vs[0] += t; vs[1] += t; vs[2] += t; return *this; }
-  inline Vec3Data<T>& operator -= (T t) { vs[0] -= t; vs[1] -= t; vs[2] -= t; return *this; }
-  inline Vec3Data<T>& operator *= (T t) { vs[0] *= t; vs[1] *= t; vs[2] *= t; return *this; }
-  inline Vec3Data<T>& operator /= (T t) { T inv_t = 1.0 / t; vs[0] *= inv_t; vs[1] *= inv_t; vs[2] *= inv_t; return *this; }
-  inline Vec3Data<T> operator - () const { return Vec3Data<T>(-vs[0], -vs[1], -vs[2]); }
-};
-
-
-template <typename T>
-static inline Vec3Data<T> cross_prod(const Vec3Data<T>& l, const Vec3Data<T>& r)
-{
-  return Vec3Data<T>(l.vs[1] * r.vs[2] - l.vs[2] * r.vs[1], 
-                     l.vs[2] * r.vs[0] - l.vs[0] * r.vs[2],
-                     l.vs[0] * r.vs[1] - l.vs[1] * r.vs[0]);
-}
-
-template <typename T>
-static inline T dot_prod3(const Vec3Data<T>& l, const Vec3Data<T>& r)
-{
-  return l.vs[0] * r.vs[0] + l.vs[1] * r.vs[1] + l.vs[2] * r.vs[2];
-}
-
-
-template <typename T>
-static inline Vec3Data<T> min(const Vec3Data<T>& x, const Vec3Data<T>& y)
-{
-  return Vec3Data<T>(std::min(x.vs[0], y.vs[0]), std::min(x.vs[1], y.vs[1]), std::min(x.vs[2], y.vs[2]));
-}
-
-template <typename T>
-static inline Vec3Data<T> max(const Vec3Data<T>& x, const Vec3Data<T>& y)
-{
-  return Vec3Data<T>(std::max(x.vs[0], y.vs[0]), std::max(x.vs[1], y.vs[1]), std::max(x.vs[2], y.vs[2]));
-}
-
-template <typename T>
-static inline Vec3Data<T> abs(const Vec3Data<T>& x)
-{
-  return Vec3Data<T>(std::abs(x.vs[0]), std::abs(x.vs[1]), std::abs(x.vs[2]));
-}
-
-template <typename T>
-static inline bool equal(const Vec3Data<T>& x, const Vec3Data<T>& y, T epsilon)
-{
-  return ((x.vs[0] - y.vs[0] < epsilon) &&
-          (x.vs[0] - y.vs[0] > -epsilon) &&
-          (x.vs[1] - y.vs[1] < epsilon) &&
-          (x.vs[1] - y.vs[1] > -epsilon) &&
-          (x.vs[2] - y.vs[2] < epsilon) &&
-          (x.vs[2] - y.vs[2] > -epsilon));
-}
-
-
-template<typename T>
-struct Matrix3Data
-{
-  typedef T meta_type;
-  typedef Vec3Data<T> vector_type;
-  
-  Vec3Data<T> rs[3];
-  Matrix3Data() {};
-
-  Matrix3Data(T xx, T xy, T xz,
-              T yx, T yy, T yz,
-              T zx, T zy, T zz)
-  {
-    setValue(xx, xy, xz,
-             yx, yy, yz,
-             zx, zy, zz);
-  }
-
-  Matrix3Data(const Vec3Data<T>& v1, const Vec3Data<T>& v2, const Vec3Data<T>& v3)
-  {
-    rs[0] = v1;
-    rs[1] = v2;
-    rs[2] = v3;
-  }
-
-  Matrix3Data(const Matrix3Data<T>& other)
-  {
-    rs[0] = other.rs[0];
-    rs[1] = other.rs[1];
-    rs[2] = other.rs[2];
-  }
-
-  inline Vec3Data<T> getColumn(size_t i) const
-  {
-    return Vec3Data<T>(rs[0][i], rs[1][i], rs[2][i]);
-  }
-
-  inline const Vec3Data<T>& getRow(size_t i) const
-  {
-    return rs[i];
-  }
-
-  inline T operator() (size_t i, size_t j) const 
-  {
-    return rs[i][j];
-  }
-
-  inline T& operator() (size_t i, size_t j)
-  {
-    return rs[i][j];
-  }
-
-  inline Vec3Data<T> operator * (const Vec3Data<T>& v) const
-  {
-    return Vec3Data<T>(dot_prod3(rs[0], v), dot_prod3(rs[1], v), dot_prod3(rs[2], v));
-  }
-
-  inline Matrix3Data<T> operator * (const Matrix3Data<T>& other) const
-  {
-    return Matrix3Data<T>(other.transposeDotX(rs[0]), other.transposeDotY(rs[0]), other.transposeDotZ(rs[0]),
-                          other.transposeDotX(rs[1]), other.transposeDotY(rs[1]), other.transposeDotZ(rs[1]),
-                          other.transposeDotX(rs[2]), other.transposeDotY(rs[2]), other.transposeDotZ(rs[2]));
-  }
-
-  inline Matrix3Data<T> operator + (const Matrix3Data<T>& other) const
-  {
-    return Matrix3Data<T>(rs[0] + other.rs[0], rs[1] + other.rs[1], rs[2] + other.rs[2]);
-  }
-
-  inline Matrix3Data<T> operator - (const Matrix3Data<T>& other) const
-  {
-    return Matrix3Data<T>(rs[0] - other.rs[0], rs[1] - other.rs[1], rs[2] - other.rs[2]);
-  }
-
-  inline Matrix3Data<T> operator + (T c) const
-  {
-    return Matrix3Data<T>(rs[0] + c, rs[1] + c, rs[2] + c);
-  }
-
-  inline Matrix3Data<T> operator - (T c) const
-  {
-    return Matrix3Data<T>(rs[0] - c, rs[1] - c, rs[2] - c);
-  }
-
-  inline Matrix3Data<T> operator * (T c) const
-  {
-    return Matrix3Data<T>(rs[0] * c, rs[1] * c, rs[2] * c);
-  }
-
-  inline Matrix3Data<T> operator / (T c) const
-  {
-    return Matrix3Data<T>(rs[0] / c, rs[1] / c, rs[2] / c);
-  }
-
-  inline Matrix3Data<T>& operator *= (const Matrix3Data<T>& other)
-  {
-    rs[0].setValue(other.transposeDotX(rs[0]), other.transposeDotY(rs[0]), other.transposeDotZ(rs[0]));
-    rs[1].setValue(other.transposeDotX(rs[1]), other.transposeDotY(rs[1]), other.transposeDotZ(rs[1]));
-    rs[2].setValue(other.transposeDotX(rs[2]), other.transposeDotY(rs[2]), other.transposeDotZ(rs[2]));
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator += (const Matrix3Data<T>& other)
-  {
-    rs[0] += other.rs[0];
-    rs[1] += other.rs[1];
-    rs[2] += other.rs[2];
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator -= (const Matrix3Data<T>& other)
-  {
-    rs[0] -= other.rs[0];
-    rs[1] -= other.rs[1];
-    rs[2] -= other.rs[2];
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator += (T c)
-  {
-    rs[0] += c;
-    rs[1] += c;
-    rs[2] += c;
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator - (T c)
-  {
-    rs[0] -= c;
-    rs[1] -= c;
-    rs[2] -= c;
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator * (T c)
-  {
-    rs[0] *= c;
-    rs[1] *= c;
-    rs[2] *= c;
-    return *this;
-  }
-
-  inline Matrix3Data<T>& operator / (T c)
-  {
-    rs[0] /= c;
-    rs[1] /= c;
-    rs[2] /= c;
-    return *this;
-  }
-
-
-  void setIdentity() 
-  {
-    setValue((T)1, (T)0, (T)0,
-             (T)0, (T)1, (T)0,
-             (T)0, (T)0, (T)1);
-  }
-
-  void setZero()
-  {
-    setValue((T)0);
-  }
-
-  static const Matrix3Data<T>& getIdentity()
-  {
-    static const Matrix3Data<T> I((T)1, (T)0, (T)0,
-                                  (T)0, (T)1, (T)0,
-                                  (T)0, (T)0, (T)1);
-    return I;
-  }
-
-  T determinant() const
-  {
-    return dot_prod3(rs[0], cross_prod(rs[1], rs[2]));
-  }
-
-  Matrix3Data<T>& transpose()
-  {
-    register T tmp = rs[0][1];
-    rs[0][1] = rs[1][0];
-    rs[1][0] = tmp;
-    
-    tmp = rs[0][2];
-    rs[0][2] = rs[2][0];
-    rs[2][0] = tmp;
-    
-    tmp = rs[2][1];
-    rs[2][1] = rs[1][2];
-    rs[1][2] = tmp;
-    return *this;
-  }
-
-  Matrix3Data<T>& inverse()
-  {
-    T det = determinant();
-    register T inrsdet = 1 / det;
-    
-    setValue((rs[1][1] * rs[2][2] - rs[1][2] * rs[2][1]) * inrsdet,
-             (rs[0][2] * rs[2][1] - rs[0][1] * rs[2][2]) * inrsdet,
-             (rs[0][1] * rs[1][2] - rs[0][2] * rs[1][1]) * inrsdet,
-             (rs[1][2] * rs[2][0] - rs[1][0] * rs[2][2]) * inrsdet,
-             (rs[0][0] * rs[2][2] - rs[0][2] * rs[2][0]) * inrsdet,
-             (rs[0][2] * rs[1][0] - rs[0][0] * rs[1][2]) * inrsdet,
-             (rs[1][0] * rs[2][1] - rs[1][1] * rs[2][0]) * inrsdet,
-             (rs[0][1] * rs[2][0] - rs[0][0] * rs[2][1]) * inrsdet,
-             (rs[0][0] * rs[1][1] - rs[0][1] * rs[1][0]) * inrsdet);
-
-    return *this;
-  }
-
-  Matrix3Data<T> transposeTimes(const Matrix3Data<T>& m) const
-  {
-    return Matrix3Data<T>(rs[0][0] * m.rs[0][0] + rs[1][0] * m.rs[1][0] + rs[2][0] * m.rs[2][0],
-                          rs[0][0] * m.rs[0][1] + rs[1][0] * m.rs[1][1] + rs[2][0] * m.rs[2][1],
-                          rs[0][0] * m.rs[0][2] + rs[1][0] * m.rs[1][2] + rs[2][0] * m.rs[2][2],
-                          rs[0][1] * m.rs[0][0] + rs[1][1] * m.rs[1][0] + rs[2][1] * m.rs[2][0],
-                          rs[0][1] * m.rs[0][1] + rs[1][1] * m.rs[1][1] + rs[2][1] * m.rs[2][1],
-                          rs[0][1] * m.rs[0][2] + rs[1][1] * m.rs[1][2] + rs[2][1] * m.rs[2][2],
-                          rs[0][2] * m.rs[0][0] + rs[1][2] * m.rs[1][0] + rs[2][2] * m.rs[2][0],
-                          rs[0][2] * m.rs[0][1] + rs[1][2] * m.rs[1][1] + rs[2][2] * m.rs[2][1],
-                          rs[0][2] * m.rs[0][2] + rs[1][2] * m.rs[1][2] + rs[2][2] * m.rs[2][2]);
-  }
-   
-  Matrix3Data<T> timesTranspose(const Matrix3Data<T>& m) const
-  {
-    return Matrix3Data<T>(dot_prod3(rs[0], m[0]), dot_prod3(rs[0], m[1]), dot_prod3(rs[0], m[2]),
-                          dot_prod3(rs[1], m[0]), dot_prod3(rs[1], m[1]), dot_prod3(rs[1], m[2]),
-                          dot_prod3(rs[2], m[0]), dot_prod3(rs[2], m[1]), dot_prod3(rs[2], m[2]));
-  }
-
-
-  Vec3Data<T> transposeTimes(const Vec3Data<T>& v) const
-  {
-    return Vec3Data<T>(transposeDotX(v), transposeDotY(v), transposeDotZ(v));
-  }
-
-  inline T transposeDotX(const Vec3Data<T>& v) const
-  {
-    return rs[0][0] * v[0] + rs[1][0] * v[1] + rs[2][0] * v[2];
-  }
-
-  inline T transposeDotY(const Vec3Data<T>& v) const
-  {
-    return rs[0][1] * v[0] + rs[1][1] * v[1] + rs[2][1] * v[2];
-  }
-
-  inline T transposeDotZ(const Vec3Data<T>& v) const
-  {
-    return rs[0][2] * v[0] + rs[1][2] * v[1] + rs[2][2] * v[2];
-  }
-
-  inline T transposeDot(size_t i, const Vec3Data<T>& v) const
-  {
-    return rs[0][i] * v[0] + rs[1][i] * v[1] + rs[2][i] * v[2];
-  }
-
-  inline T dotX(const Vec3Data<T>& v) const
-  {
-    return rs[0][0] * v[0] + rs[0][1] * v[1] + rs[0][2] * v[2];
-  }
-
-  inline T dotY(const Vec3Data<T>& v) const
-  {
-    return rs[1][0] * v[0] + rs[1][1] * v[1] + rs[1][2] * v[2];
-  }
-
-  inline T dotZ(const Vec3Data<T>& v) const
-  {
-    return rs[2][0] * v[0] + rs[2][1] * v[1] + rs[2][2] * v[2];
-  }
-
-  inline T dot(size_t i, const Vec3Data<T>& v) const
-  {
-    return rs[i][0] * v[0] + rs[i][1] * v[1] + rs[i][2] * v[2];
-  }
-    
-  inline void setValue(T xx, T xy, T xz,
-                       T yx, T yy, T yz,
-                       T zx, T zy, T zz)
-  {
-    rs[0].setValue(xx, xy, xz);
-    rs[1].setValue(yx, yy, yz);
-    rs[2].setValue(zx, zy, zz);
-  }
-    
-  inline void setValue(T x)
-  {
-    rs[0].setValue(x);
-    rs[1].setValue(x);
-    rs[2].setValue(x);
-  }
-};
-
-
-
-template<typename T>
-Matrix3Data<T> abs(const Matrix3Data<T>& m)
-{
-  return Matrix3Data<T>(abs(m.rs[0]), abs(m.rs[1]), abs(m.rs[2]));
-}
-
-template<typename T>
-Matrix3Data<T> transpose(const Matrix3Data<T>& m)
-{
-  return Matrix3Data<T>(m.rs[0][0], m.rs[1][0], m.rs[2][0],
-                        m.rs[0][1], m.rs[1][1], m.rs[2][1],
-                        m.rs[0][2], m.rs[1][2], m.rs[2][2]);
-}
-
-
-template<typename T>
-Matrix3Data<T> inverse(const Matrix3Data<T>& m)
-{
-  T det = m.determinant();
-  T inrsdet = 1 / det;
-
-  return Matrix3Data<T>((m.rs[1][1] * m.rs[2][2] - m.rs[1][2] * m.rs[2][1]) * inrsdet,
-                        (m.rs[0][2] * m.rs[2][1] - m.rs[0][1] * m.rs[2][2]) * inrsdet,
-                        (m.rs[0][1] * m.rs[1][2] - m.rs[0][2] * m.rs[1][1]) * inrsdet,
-                        (m.rs[1][2] * m.rs[2][0] - m.rs[1][0] * m.rs[2][2]) * inrsdet,
-                        (m.rs[0][0] * m.rs[2][2] - m.rs[0][2] * m.rs[2][0]) * inrsdet,
-                        (m.rs[0][2] * m.rs[1][0] - m.rs[0][0] * m.rs[1][2]) * inrsdet,
-                        (m.rs[1][0] * m.rs[2][1] - m.rs[1][1] * m.rs[2][0]) * inrsdet,
-                        (m.rs[0][1] * m.rs[2][0] - m.rs[0][0] * m.rs[2][1]) * inrsdet,
-                        (m.rs[0][0] * m.rs[1][1] - m.rs[0][1] * m.rs[1][0]) * inrsdet);
-}
-
-}
-
-}
-
-#endif
diff --git a/include/hpp/fcl/math/matrix_3f.h b/include/hpp/fcl/math/matrix_3f.h
index 5226b537..36815c14 100644
--- a/include/hpp/fcl/math/matrix_3f.h
+++ b/include/hpp/fcl/math/matrix_3f.h
@@ -40,32 +40,10 @@
 
 #include <hpp/fcl/math/vec_3f.h>
 
-#if ! FCL_HAVE_EIGEN
-# include <hpp/fcl/math/matrix_3fx.h>
-#endif
-
 namespace fcl
 {
 
-#if FCL_HAVE_EIGEN
   typedef Eigen::Matrix<FCL_REAL, 3, 3> Matrix3f;
-#elif FCL_HAVE_SSE
-  typedef Matrix3fX<details::sse_meta_f12> Matrix3f;
-#else
-  typedef Matrix3fX<details::Matrix3Data<FCL_REAL> > Matrix3f;
-#endif
-
-#if ! FCL_HAVE_EIGEN
-static inline std::ostream& operator << (std::ostream& o, const Matrix3f& m)
-{
-  o << "[(" << m(0, 0) << " " << m(0, 1) << " " << m(0, 2) << ")("
-    << m(1, 0) << " " << m(1, 1) << " " << m(1, 2) << ")(" 
-    << m(2, 0) << " " << m(2, 1) << " " << m(2, 2) << ")]";
-  return o;
-}
-#endif
-
-
 
 /// @brief Class for variance matrix in 3d
 class Variance3f
diff --git a/include/hpp/fcl/math/matrix_3fx.h b/include/hpp/fcl/math/matrix_3fx.h
deleted file mode 100644
index 1c93e7e6..00000000
--- a/include/hpp/fcl/math/matrix_3fx.h
+++ /dev/null
@@ -1,481 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Jia Pan */
-
-#ifndef FCL_MATRIX_3FX_H
-#define FCL_MATRIX_3FX_H
-
-#include <hpp/fcl/math/vec_3f.h>
-#include <Eigen/Core>
-
-namespace fcl
-{
-
-/// @brief Matrix2 class wrapper. the core data is in the template parameter class
-template<typename T>
-class Matrix3fX
-{
-public:
-  typedef typename T::meta_type U;
-  typedef typename T::vector_type S;
-  typedef Eigen::Matrix<U, 3, 3> EigenType;
-  T data;
-  
-  Matrix3fX() {}
-  Matrix3fX(U xx, U xy, U xz,
-            U yx, U yy, U yz,
-            U zx, U zy, U zz) : data(xx, xy, xz, yx, yy, yz, zx, zy, zz)
-  {}
-
-  Matrix3fX(const Vec3fX<S>& v1, const Vec3fX<S>& v2, const Vec3fX<S>& v3)
-    : data(v1.data, v2.data, v3.data) {}
-  
-  Matrix3fX(const Matrix3fX<T>& other) : data(other.data) {}
-
-  Matrix3fX(const T& data_) : data(data_) {}
-  
-  inline Vec3fX<S> getColumn(size_t i) const
-  {
-    return Vec3fX<S>(data.getColumn(i));
-  }
-
-  inline Vec3fX<S> getRow(size_t i) const
-  {
-    return Vec3fX<S>(data.getRow(i));
-  }
-
-  inline EigenType derived() const
-  {
-    EigenType ret;
-    for(int i = 0; i < 3; ++i)
-      for(int j = 0; j < 3; ++j)
-        ret(i,j) = data(i,j);
-    return ret;
-  }
-
-  inline U operator () (size_t i, size_t j) const
-  {
-    return data(i, j);
-  }
-
-  inline U& operator () (size_t i, size_t j)
-  {
-    return data(i, j);
-  }
-
-  inline Vec3fX<S> operator * (const Vec3fX<S>& v) const
-  {
-    return Vec3fX<S>(data * v.data);
-  }
-
-  inline Matrix3fX<T> operator * (const Matrix3fX<T>& m) const
-  {
-    return Matrix3fX<T>(data * m.data);
-  }
-
-  inline Matrix3fX<T> operator + (const Matrix3fX<T>& other) const
-  {
-    return Matrix3fX<T>(data + other.data);
-  }
-
-  inline Matrix3fX<T> operator - (const Matrix3fX<T>& other) const
-  {
-    return Matrix3fX<T>(data - other.data);
-  }
-
-  inline Matrix3fX<T> operator + (U c) const
-  {
-    return Matrix3fX<T>(data + c);
-  }
-
-  inline Matrix3fX<T> operator - (U c) const
-  {
-    return Matrix3fX<T>(data - c);
-  }
-
-  inline Matrix3fX<T> operator * (U c) const
-  {
-    return Matrix3fX<T>(data * c);
-  }
-
-  inline Matrix3fX<T> operator / (U c) const
-  {
-    return Matrix3fX<T>(data / c);
-  }
-
-  inline Matrix3fX<T>& operator *= (const Matrix3fX<T>& other)
-  {
-    data *= other.data;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator += (const Matrix3fX<T>& other)
-  {
-    data += other.data;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator -= (const Matrix3fX<T>& other)
-  {
-    data -= other.data;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator += (U c) 
-  {
-    data += c;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator -= (U c)
-  {
-    data -= c;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator *= (U c)
-  {
-    data *= c;
-    return *this;
-  }
-
-  inline Matrix3fX<T>& operator /= (U c)
-  {
-    data /= c;
-    return *this;
-  }
-
-  inline void setIdentity()
-  {
-    data.setIdentity();
-  }
-
-  inline bool isIdentity () const
-  {
-    return
-      data (0,0) == 1 && data (0,1) == 0 && data (0,2) == 0 &&
-      data (1,0) == 0 && data (1,1) == 1 && data (1,2) == 0 &&
-      data (2,0) == 0 && data (2,1) == 0 && data (2,2) == 1;
-  }
-
-  inline void setZero()
-  {
-    data.setZero();
-  }
-
-  /// @brief Set the matrix from euler angles YPR around ZYX axes
-  /// @param eulerX Roll about X axis
-  /// @param eulerY Pitch around Y axis
-  /// @param eulerZ Yaw aboud Z axis
-  ///  
-  /// These angles are used to produce a rotation matrix. The euler
-  /// angles are applied in ZYX order. I.e a vector is first rotated 
-  /// about X then Y and then Z
-  inline void setEulerZYX(FCL_REAL eulerX, FCL_REAL eulerY, FCL_REAL eulerZ)
-  {
-    FCL_REAL ci(cos(eulerX));
-    FCL_REAL cj(cos(eulerY));
-    FCL_REAL ch(cos(eulerZ));
-    FCL_REAL si(sin(eulerX));
-    FCL_REAL sj(sin(eulerY));
-    FCL_REAL sh(sin(eulerZ));
-    FCL_REAL cc = ci * ch;
-    FCL_REAL cs = ci * sh;
-    FCL_REAL sc = si * ch;
-    FCL_REAL ss = si * sh;
-
-    setValue(cj * ch, sj * sc - cs, sj * cc + ss,
-             cj * sh, sj * ss + cc, sj * cs - sc, 
-             -sj,     cj * si,      cj * ci);
-
-  }
-
-  /// @brief Set the matrix from euler angles using YPR around YXZ respectively
-  /// @param yaw Yaw about Y axis
-  /// @param pitch Pitch about X axis
-  /// @param roll Roll about Z axis 
-  void setEulerYPR(FCL_REAL yaw, FCL_REAL pitch, FCL_REAL roll)
-  {
-    setEulerZYX(roll, pitch, yaw);
-  }
-
-  inline U determinant() const
-  {
-    return data.determinant();
-  }
-
-  Matrix3fX<T>& transpose() 
-  {
-    data.transpose();
-    return *this;
-  }
-
-  Matrix3fX<T>& inverse()
-  {
-    data.inverse();
-    return *this;
-  }
-
-  Matrix3fX<T>& abs()
-  {
-    data.abs();
-    return *this;
-  }
-
-  static const Matrix3fX<T>& getIdentity()
-  {
-    static const Matrix3fX<T> I((U)1, (U)0, (U)0,
-                                (U)0, (U)1, (U)0,
-                                (U)0, (U)0, (U)1);
-    return I;
-  }
-
-  Matrix3fX<T> transposeTimes(const Matrix3fX<T>& other) const
-  {
-    return Matrix3fX<T>(data.transposeTimes(other.data));
-  }
-
-  Matrix3fX<T> timesTranspose(const Matrix3fX<T>& other) const
-  {
-    return Matrix3fX<T>(data.timesTranspose(other.data));
-  }
-
-  Vec3fX<S> transposeTimes(const Vec3fX<S>& v) const
-  {
-    return Vec3fX<S>(data.transposeTimes(v.data));
-  }
-
-  Matrix3fX<T> tensorTransform(const Matrix3fX<T>& m) const
-  {
-    Matrix3fX<T> res(*this);
-    res *= m;
-    return res.timesTranspose(*this);
-  }
-
-  // (1 0 0)^T (*this)^T v
-  inline U transposeDotX(const Vec3fX<S>& v) const
-  {
-    return data.transposeDot(0, v.data);
-  }
-
-  // (0 1 0)^T (*this)^T v
-  inline U transposeDotY(const Vec3fX<S>& v) const
-  {
-    return data.transposeDot(1, v.data);
-  }
-
-  // (0 0 1)^T (*this)^T v
-  inline U transposeDotZ(const Vec3fX<S>& v) const
-  {
-    return data.transposeDot(2, v.data);
-  }
-
-  // (\delta_{i3})^T (*this)^T v
-  inline U transposeDot(size_t i, const Vec3fX<S>& v) const
-  {
-    return data.transposeDot(i, v.data);
-  }
-
-  // (1 0 0)^T (*this) v
-  inline U dotX(const Vec3fX<S>& v) const
-  {
-    return data.dot(0, v.data);
-  }
-
-  // (0 1 0)^T (*this) v
-  inline U dotY(const Vec3fX<S>& v) const
-  {
-    return data.dot(1, v.data);
-  }
-
-  // (0 0 1)^T (*this) v
-  inline U dotZ(const Vec3fX<S>& v) const
-  {
-    return data.dot(2, v.data);
-  }
-
-  // (\delta_{i3})^T (*this) v
-  inline U dot(size_t i, const Vec3fX<S>& v) const
-  {
-    return data.dot(i, v.data);
-  }
-
-  inline void setValue(U xx, U xy, U xz,
-                       U yx, U yy, U yz,
-                       U zx, U zy, U zz)
-  {
-    data.setValue(xx, xy, xz, 
-                  yx, yy, yz,
-                  zx, zy, zz);
-  }
-
-  inline void setValue(U x)
-  {
-    data.setValue(x);
-  }
-};
-
-template<typename T>
-void hat(Matrix3fX<T>& mat, const Vec3fX<typename T::vector_type>& vec)
-{
-  mat.setValue(0, -vec[2], vec[1], vec[2], 0, -vec[0], -vec[1], vec[0], 0);
-}
-
-template<typename T>
-void relativeTransform(const Matrix3fX<T>& R1, const Vec3fX<typename T::vector_type>& t1,
-                       const Matrix3fX<T>& R2, const Vec3fX<typename T::vector_type>& t2,
-                       Matrix3fX<T>& R, Vec3fX<typename T::vector_type>& t)
-{
-  R = R1.transposeTimes(R2);
-  t = R1.transposeTimes(t2 - t1);
-}
-
-/// @brief compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors
-template<typename T>
-void eigen(const Matrix3fX<T>& m, typename T::meta_type dout[3], Vec3fX<typename T::vector_type> vout[3])
-{
-  Matrix3fX<T> R(m);
-  int n = 3;
-  int j, iq, ip, i;
-  typename T::meta_type tresh, theta, tau, t, sm, s, h, g, c;
-  int nrot;
-  typename T::meta_type b[3];
-  typename T::meta_type z[3];
-  typename T::meta_type v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
-  typename T::meta_type d[3];
-
-  for(ip = 0; ip < n; ++ip)
-  {
-    b[ip] = d[ip] = R(ip, ip);
-    z[ip] = 0;
-  }
-
-  nrot = 0;
-
-  for(i = 0; i < 50; ++i)
-  {
-    sm = 0;
-    for(ip = 0; ip < n; ++ip)
-      for(iq = ip + 1; iq < n; ++iq)
-        sm += std::abs(R(ip, iq));
-    if(sm == 0.0)
-    {
-      vout[0].setValue(v[0][0], v[0][1], v[0][2]);
-      vout[1].setValue(v[1][0], v[1][1], v[1][2]);
-      vout[2].setValue(v[2][0], v[2][1], v[2][2]);
-      dout[0] = d[0]; dout[1] = d[1]; dout[2] = d[2];
-      return;
-    }
-
-    if(i < 3) tresh = 0.2 * sm / (n * n);
-    else tresh = 0.0;
-
-    for(ip = 0; ip < n; ++ip)
-    {
-      for(iq= ip + 1; iq < n; ++iq)
-      {
-        g = 100.0 * std::abs(R(ip, iq));
-        if(i > 3 &&
-           std::abs(d[ip]) + g == std::abs(d[ip]) &&
-           std::abs(d[iq]) + g == std::abs(d[iq]))
-          R(ip, iq) = 0.0;
-        else if(std::abs(R(ip, iq)) > tresh)
-        {
-          h = d[iq] - d[ip];
-          if(std::abs(h) + g == std::abs(h)) t = (R(ip, iq)) / h;
-          else
-          {
-            theta = 0.5 * h / (R(ip, iq));
-            t = 1.0 /(std::abs(theta) + std::sqrt(1.0 + theta * theta));
-            if(theta < 0.0) t = -t;
-          }
-          c = 1.0 / std::sqrt(1 + t * t);
-          s = t * c;
-          tau = s / (1.0 + c);
-          h = t * R(ip, iq);
-          z[ip] -= h;
-          z[iq] += h;
-          d[ip] -= h;
-          d[iq] += h;
-          R(ip, iq) = 0.0;
-          for(j = 0; j < ip; ++j) { g = R(j, ip); h = R(j, iq); R(j, ip) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
-          for(j = ip + 1; j < iq; ++j) { g = R(ip, j); h = R(j, iq); R(ip, j) = g - s * (h + g * tau); R(j, iq) = h + s * (g - h * tau); }
-          for(j = iq + 1; j < n; ++j) { g = R(ip, j); h = R(iq, j); R(ip, j) = g - s * (h + g * tau); R(iq, j) = h + s * (g - h * tau); }
-          for(j = 0; j < n; ++j) { g = v[j][ip]; h = v[j][iq]; v[j][ip] = g - s * (h + g * tau); v[j][iq] = h + s * (g - h * tau); }
-          nrot++;
-        }
-      }
-    }
-    for(ip = 0; ip < n; ++ip)
-    {
-      b[ip] += z[ip];
-      d[ip] = b[ip];
-      z[ip] = 0.0;
-    }
-  }
-
-  std::cerr << "eigen: too many iterations in Jacobi transform." << std::endl;
-
-  return;
-}
-
-template<typename T>
-Matrix3fX<T> abs(const Matrix3fX<T>& R) 
-{
-  return Matrix3fX<T>(abs(R.data));
-}
-
-template<typename T>
-Matrix3fX<T> transpose(const Matrix3fX<T>& R)
-{
-  return Matrix3fX<T>(transpose(R.data));
-}
-
-template<typename T>
-Matrix3fX<T> inverse(const Matrix3fX<T>& R)
-{
-  return Matrix3fX<T>(inverse(R.data));
-}
-
-template<typename T>
-typename T::meta_type quadraticForm(const Matrix3fX<T>& R, const Vec3fX<typename T::vector_type>& v)
-{
-  return v.dot(R * v);
-}
-
-}
-
-#endif
diff --git a/include/hpp/fcl/math/tools.h b/include/hpp/fcl/math/tools.h
index 08e0628d..23a4f18d 100644
--- a/include/hpp/fcl/math/tools.h
+++ b/include/hpp/fcl/math/tools.h
@@ -49,9 +49,6 @@
 #include <iostream>
 #include <limits>
 
-#define FCL_CCD_INTERVALVECTOR_PLUGIN <hpp/fcl/eigen/plugins/ccd/interval-vector.h>
-#define FCL_CCD_MATRIXVECTOR_PLUGIN <hpp/fcl/eigen/plugins/ccd/interval-matrix.h>
-
 namespace fcl
 {
 
@@ -64,29 +61,6 @@ static inline typename Derived::Scalar triple(
   return x.derived().dot(y.derived().cross(z.derived()));
 }
 
-
-/*
-template<typename Derived, typename OtherDerived>
-static inline const typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Min
- min(const Eigen::MatrixBase<Derived>& x, const Eigen::MatrixBase<OtherDerived>& y)
-{
-  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Min (x.derived(), y.derived());
-}
-
-template<typename Derived, typename OtherDerived>
-static inline const typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Max
- max(const Eigen::MatrixBase<Derived>& x, const Eigen::MatrixBase<OtherDerived>& y)
-{
-  return typename Eigen::BinaryReturnType<const Derived, const OtherDerived>::Max (x.derived(), y.derived());
-}
-
-template<typename Derived>
-static inline const typename Eigen::UnaryReturnType<const Derived>::Abs
-abs(const Eigen::MatrixBase<Derived>& x)
-{
-  return typename Eigen::UnaryReturnType<const Derived>::Abs (x.derived());
-} */
-
 template<typename Derived1, typename Derived2, typename Derived3>
 void generateCoordinateSystem(
     const Eigen::MatrixBase<Derived1>& _w,
diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h
index 1ecc46b1..4322ecdb 100644
--- a/include/hpp/fcl/math/vec_3f.h
+++ b/include/hpp/fcl/math/vec_3f.h
@@ -41,20 +41,9 @@
 #include <hpp/fcl/config-fcl.hh>
 #include <hpp/fcl/data_types.h>
 
-#if FCL_HAVE_EIGEN
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 #include <hpp/fcl/math/tools.h>
-#elif FCL_HAVE_SSE
-# include <hpp/fcl/simd/math_simd_details.h>
-#else
-# include <hpp/fcl/math/math_details.h>
-#endif
-
-#if FCL_HAVE_EIGEN
-#else
-# include <hpp/fcl/math/vec_3fx.h>
-#endif
 
 #include <cmath>
 #include <iostream>
@@ -63,21 +52,7 @@
 
 namespace fcl
 {
-
-#if FCL_HAVE_EIGEN
   typedef Eigen::Matrix<FCL_REAL, 3, 1> Vec3f;
-#elif FCL_HAVE_SSE
-  typedef Vec3fX<details::sse_meta_f4> Vec3f;
-#else
-  typedef Vec3fX<details::Vec3Data<FCL_REAL> > Vec3f;
-#endif
-
-static inline std::ostream& operator << (std::ostream& o, const Vec3f& v)
-{
-  o << "(" << v[0] << " " << v[1] << " " << v[2] << ")";
-  return o;
-}
-
 }
 
 
diff --git a/include/hpp/fcl/math/vec_3fx.h b/include/hpp/fcl/math/vec_3fx.h
deleted file mode 100644
index adbd4a28..00000000
--- a/include/hpp/fcl/math/vec_3fx.h
+++ /dev/null
@@ -1,245 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Jia Pan */
-
-#ifndef FCL_VEC_3FX_H
-#define FCL_VEC_3FX_H
-
-#include <hpp/fcl/config-fcl.hh>
-#include <hpp/fcl/data_types.h>
-
-#include <cmath>
-#include <iostream>
-#include <limits>
-
-#include <Eigen/Core>
-
-namespace fcl
-{
-
-/// @brief Vector3 class wrapper. The core data is in the template parameter class.
-template <typename T>
-class Vec3fX
-{
-public:
-  typedef typename T::meta_type U;
-  typedef Eigen::Matrix<U, 3, 1> EigenType;
-
-  /// @brief interval vector3 data
-  T data;
-
-  Vec3fX() {}
-  Vec3fX(const Vec3fX& other) : data(other.data) {}
-
-  /// @brief create Vector (x, y, z)
-  Vec3fX(U x, U y, U z) : data(x, y, z) {}
-
-  /// @brief create vector (x, x, x)
-  Vec3fX(U x) : data(x) {}
-
-  /// @brief create vector using the internal data type
-  Vec3fX(const T& data_) : data(data_) {}
-
-  inline EigenType derived() const
-  {
-    return EigenType (data[0],data[1],data[2]);
-  }
-
-  inline U operator [] (size_t i) const { return data[i]; }
-  inline U& operator [] (size_t i) { return data[i]; }
-
-  inline Vec3fX operator + (const Vec3fX& other) const { return Vec3fX(data + other.data); }
-  inline Vec3fX operator - (const Vec3fX& other) const { return Vec3fX(data - other.data); }
-  inline Vec3fX operator * (const Vec3fX& other) const { return Vec3fX(data * other.data); }
-  inline Vec3fX operator / (const Vec3fX& other) const { return Vec3fX(data / other.data); }
-  inline Vec3fX& operator += (const Vec3fX& other) { data += other.data; return *this; }
-  inline Vec3fX& operator -= (const Vec3fX& other) { data -= other.data; return *this; }
-  inline Vec3fX& operator *= (const Vec3fX& other) { data *= other.data; return *this; }
-  inline Vec3fX& operator /= (const Vec3fX& other) { data /= other.data; return *this; }
-  inline Vec3fX operator + (U t) const { return Vec3fX(data + t); }
-  inline Vec3fX operator - (U t) const { return Vec3fX(data - t); }
-  inline Vec3fX operator * (U t) const { return Vec3fX(data * t); }
-  inline Vec3fX operator / (U t) const { return Vec3fX(data / t); }
-  inline Vec3fX& operator += (U t) { data += t; return *this; }
-  inline Vec3fX& operator -= (U t) { data -= t; return *this; }
-  inline Vec3fX& operator *= (U t) { data *= t; return *this; }
-  inline Vec3fX& operator /= (U t) { data /= t; return *this; }
-  inline Vec3fX operator - () const { return Vec3fX(-data); }
-  inline Vec3fX cross(const Vec3fX& other) const { return Vec3fX(details::cross_prod(data, other.data)); }
-  inline U dot(const Vec3fX& other) const { return details::dot_prod3(data, other.data); }
-  inline Vec3fX& normalize()
-  {
-    U sqr_length = details::dot_prod3(data, data);
-    if(sqr_length > 0)
-      *this /= (U)sqrt(sqr_length);
-    return *this;
-  }
-
-  inline Vec3fX& normalize(bool* signal)
-  {
-    U sqr_length = details::dot_prod3(data, data);
-    if(sqr_length > 0)
-    {
-      *this /= (U)sqrt(sqr_length);
-      *signal = true;
-    }
-    else
-      *signal = false;
-    return *this;
-  }
-
-  inline Vec3fX& abs() 
-  {
-    data = abs(data);
-    return *this;
-  }
-
-  inline U norm() const { return sqrt(details::dot_prod3(data, data)); }
-  inline U squaredNorm() const { return details::dot_prod3(data, data); }
-  inline void setValue(U x, U y, U z) { data.setValue(x, y, z); }
-  inline void setValue(U x) { data.setValue(x); }
-  inline void setZero () {data.setValue (0); }
-  inline bool equal(const Vec3fX& other, U epsilon = std::numeric_limits<U>::epsilon() * 100) const { return details::equal(data, other.data, epsilon); }
-
-  bool operator == (const Vec3fX& other) const
-  {
-    return equal(other, 0);
-  }
-
-  bool operator != (const Vec3fX& other) const
-  {
-    return !(*this == other);
-  }
-
-
-  inline Vec3fX<T>& ubound(const Vec3fX<T>& u)
-  {
-    data.ubound(u.data);
-    return *this;
-  }
-
-  inline Vec3fX<T>& lbound(const Vec3fX<T>& l)
-  {
-    data.lbound(l.data);
-    return *this;
-  }
-
-  bool isZero() const
-  {
-    return (data[0] == 0) && (data[1] == 0) && (data[2] == 0);
-  }
-
-};
-
-template<typename T>
-static inline Vec3fX<T> normalize(const Vec3fX<T>& v)
-{
-  typename T::meta_type sqr_length = details::dot_prod3(v.data, v.data);
-  if(sqr_length > 0)
-    return v / (typename T::meta_type)sqrt(sqr_length);
-  else
-    return v;
-}
-
-template <typename T>
-static inline typename T::meta_type triple(const Vec3fX<T>& x, const Vec3fX<T>& y, const Vec3fX<T>& z)
-{
-  return x.dot(y.cross(z));
-}
-
-template <typename T>
-std::ostream& operator << (std::ostream& out, const Vec3fX<T>& x)
-{
-  out << x[0] << " " << x[1] << " " << x[2];
-  return out;
-}
-
-template <typename T>
-static inline Vec3fX<T> min(const Vec3fX<T>& x, const Vec3fX<T>& y)
-{
-  return Vec3fX<T>(details::min(x.data, y.data));
-}
-
-template <typename T>
-static inline Vec3fX<T> max(const Vec3fX<T>& x, const Vec3fX<T>& y)
-{
-  return Vec3fX<T>(details::max(x.data, y.data));
-}
-
-template <typename T>
-static inline Vec3fX<T> abs(const Vec3fX<T>& x)
-{
-  return Vec3fX<T>(details::abs(x.data));
-}
-
-template <typename T>
-void generateCoordinateSystem(const Vec3fX<T>& w, Vec3fX<T>& u, Vec3fX<T>& v)
-{
-  typedef typename T::meta_type U;
-  U inv_length;
-  if(std::abs(w[0]) >= std::abs(w[1]))
-  {
-    inv_length = (U)1.0 / sqrt(w[0] * w[0] + w[2] * w[2]);
-    u[0] = -w[2] * inv_length;
-    u[1] = (U)0;
-    u[2] = w[0] * inv_length;
-    v[0] = w[1] * u[2];
-    v[1] = w[2] * u[0] - w[0] * u[2];
-    v[2] = -w[1] * u[0];
-  }
-  else
-  {
-    inv_length = (U)1.0 / sqrt(w[1] * w[1] + w[2] * w[2]);
-    u[0] = (U)0;
-    u[1] = w[2] * inv_length;
-    u[2] = -w[1] * inv_length;
-    v[0] = w[1] * u[2] - w[2] * u[1];
-    v[1] = -w[0] * u[2];
-    v[2] = w[0] * u[1];
-  }
-}
-
- template <typename T>
-   inline Vec3fX <T> operator * (const typename Vec3fX <T>::U& t,
-				 const Vec3fX <T>& v)
-   {
-     return Vec3fX <T> (v.data * t);
-   }
-
-}
-
-
-#endif
diff --git a/include/hpp/fcl/simd/math_simd_details.h b/include/hpp/fcl/simd/math_simd_details.h
deleted file mode 100644
index d6dec69f..00000000
--- a/include/hpp/fcl/simd/math_simd_details.h
+++ /dev/null
@@ -1,1143 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Jia Pan */
-
-
-#ifndef FCL_MATH_SIMD_DETAILS_H
-#define FCL_MATH_SIMD_DETAILS_H
-
-#include <hpp/fcl/data_types.h>
-
-#include <xmmintrin.h>
-#if defined (__SSE3__)
-#include <pmmintrin.h>
-#endif
-#if defined (__SSE4__)
-#include <smmintrin.h>
-#endif
-
-
-namespace fcl
-{
-
-/** \brief FCL internals. Ignore this :) unless you are God */
-namespace details
-{
-
-const __m128  xmms_0 = {0.f, 0.f, 0.f, 0.f};
-const __m128d xmmd_0 = {0, 0};
-
-static inline __m128 vec_sel(__m128 a, __m128 b, __m128 mask)
-{
-  return _mm_or_ps(_mm_and_ps(mask, b), _mm_andnot_ps(mask, a));
-}
-static inline __m128 vec_sel(__m128 a, __m128 b, const unsigned int* mask)
-{
-  return vec_sel(a, b, _mm_load_ps((float*)mask));
-}
-
-static inline __m128 vec_sel(__m128 a, __m128 b, unsigned int mask)
-{
-  return vec_sel(a, b, _mm_set1_ps(*(float*)&mask));
-}
-
-#define vec_splat(a, e) _mm_shuffle_ps((a), (a), _MM_SHUFFLE((e), (e), (e), (e)))
-#define vec_splatd(a, e) _mm_shuffle_pd((a), (a), _MM_SHUFFLE2((e), (e)))
-
-#define _mm_ror_ps(x, e) (((e) % 4) ? _mm_shuffle_ps((x), (x), _MM_SHUFFLE(((e)+3)%4, ((e)+2)%4, ((e)+1)%4, (e)%4)) : (x))
-
-#define _mm_rol_ps(x, e) (((e) % 4) ? _mm_shuffle_ps((x), (x), _MM_SHUFFLE((7-(e))%4, (6-(e))%4, (5-(e))%4, (4-(e))%4)) : (x))
-
-static inline __m128 newtonraphson_rsqrt4(const __m128 v)
-{
-  static const union { float i[4]; __m128 m; } _half4 __attribute__ ((aligned(16))) = {{.5f, .5f, .5f, .5f}};
-  static const union { float i[4]; __m128 m; } _three __attribute__ ((aligned(16))) = {{3.f, 3.f, 3.f, 3.f}};
-  __m128 approx = _mm_rsqrt_ps(v);
-  __m128 muls = _mm_mul_ps(_mm_mul_ps(v, approx), approx);
-  return _mm_mul_ps(_mm_mul_ps(_half4.m, approx), _mm_sub_ps(_three.m, muls));
-}
-
-struct sse_meta_f4
-{
-  typedef float meta_type;
-
-  union {float vs[4]; __m128 v; }; 
-  sse_meta_f4() : v(_mm_set1_ps(0)) {}
-  sse_meta_f4(float x) : v(_mm_set1_ps(x)) {}
-  sse_meta_f4(float* px) : v(_mm_load_ps(px)) {}
-  sse_meta_f4(__m128 x) : v(x) {}
-  sse_meta_f4(float x, float y, float z, float w = 1) : v(_mm_setr_ps(x, y, z, w)) {}
-  inline void setValue(float x, float y, float z, float w = 1) { v = _mm_setr_ps(x, y, z, w); }
-  inline void setValue(float x) { v = _mm_set1_ps(x); }
-  inline void setValue(__m128 x) { v = x; }
-
-  inline sse_meta_f4& ubound(const sse_meta_f4& u)
-  {
-    v = _mm_min_ps(v, u.v);
-    return *this;
-  }
-
-  inline sse_meta_f4& lbound(const sse_meta_f4& l)
-  {
-    v = _mm_max_ps(v, l.v);
-    return *this;
-  }
-  
-  inline void* operator new [] (size_t n) { return _mm_malloc(n, 16); }
-  inline void operator delete [] (void* x) { if(x) _mm_free(x); }
-  inline float operator [] (size_t i) const { return vs[i]; }
-  inline float& operator [] (size_t i) { return vs[i]; }
-
-  inline sse_meta_f4 operator + (const sse_meta_f4& other) const { return sse_meta_f4(_mm_add_ps(v, other.v)); }
-  inline sse_meta_f4 operator - (const sse_meta_f4& other) const { return sse_meta_f4(_mm_sub_ps(v, other.v)); }
-  inline sse_meta_f4 operator * (const sse_meta_f4& other) const { return sse_meta_f4(_mm_mul_ps(v, other.v)); }
-  inline sse_meta_f4 operator / (const sse_meta_f4& other) const { return sse_meta_f4(_mm_div_ps(v, other.v)); }
-  inline sse_meta_f4& operator += (const sse_meta_f4& other) { v = _mm_add_ps(v, other.v); return *this; }
-  inline sse_meta_f4& operator -= (const sse_meta_f4& other) { v = _mm_sub_ps(v, other.v); return *this; }
-  inline sse_meta_f4& operator *= (const sse_meta_f4& other) { v = _mm_mul_ps(v, other.v); return *this; }
-  inline sse_meta_f4& operator /= (const sse_meta_f4& other) { v = _mm_div_ps(v, other.v); return *this; }
-  inline sse_meta_f4 operator + (float t) const { return sse_meta_f4(_mm_add_ps(v, _mm_set1_ps(t))); }
-  inline sse_meta_f4 operator - (float t) const { return sse_meta_f4(_mm_sub_ps(v, _mm_set1_ps(t))); }
-  inline sse_meta_f4 operator * (float t) const { return sse_meta_f4(_mm_mul_ps(v, _mm_set1_ps(t))); }
-  inline sse_meta_f4 operator / (float t) const { return sse_meta_f4(_mm_div_ps(v, _mm_set1_ps(t))); }
-  inline sse_meta_f4& operator += (float t) { v = _mm_add_ps(v, _mm_set1_ps(t)); return *this; }
-  inline sse_meta_f4& operator -= (float t) { v = _mm_sub_ps(v, _mm_set1_ps(t)); return *this; }
-  inline sse_meta_f4& operator *= (float t) { v = _mm_mul_ps(v, _mm_set1_ps(t)); return *this; }
-  inline sse_meta_f4& operator /= (float t) { v = _mm_div_ps(v, _mm_set1_ps(t)); return *this; }
-  inline sse_meta_f4 operator - () const 
-  {
-    static const union { int i[4]; __m128 m; } negativemask __attribute__ ((aligned(16))) = {{0x80000000, 0x80000000, 0x80000000, 0x80000000}};
-    return sse_meta_f4(_mm_xor_ps(negativemask.m, v));                     
-  }
-} __attribute__ ((aligned (16)));
-
-struct sse_meta_d4
-{
-  typedef double meta_type;
-
-  union {double vs[4]; __m128d v[2]; };
-  sse_meta_d4()
-  {
-    setValue(0.0);
-  }
-                    
-  sse_meta_d4(double x)
-  {
-    setValue(x);
-  }
-  
-  sse_meta_d4(double* px)
-  {
-    v[0] = _mm_load_pd(px);
-    v[1] = _mm_set_pd(0, *(px + 2));
-  }
-  
-  sse_meta_d4(__m128d x, __m128d y)
-  {
-    v[0] = x;
-    v[1] = y;
-  }
-
-  sse_meta_d4(double x, double y, double z, double w = 0)
-  {
-    setValue(x, y, z, w);
-  }
-
-  inline void setValue(double x, double y, double z, double w = 0)
-  {
-    v[0] = _mm_setr_pd(x, y);
-    v[1] = _mm_setr_pd(z, w);
-  }
-
-  inline void setValue(double x)
-  {
-    v[0] = _mm_set1_pd(x);
-    v[1] = v[0];
-  }
-
-  inline void setValue(__m128d x, __m128d y)
-  {
-    v[0] = x;
-    v[1] = y;
-  }
-
-  inline sse_meta_d4& ubound(const sse_meta_d4& u)
-  {
-    v[0] = _mm_min_pd(v[0], u.v[0]);
-    v[1] = _mm_min_pd(v[1], u.v[1]);
-    return *this;
-  }
-
-  inline sse_meta_d4& lbound(const sse_meta_d4& l)
-  {
-    v[0] = _mm_max_pd(v[0], l.v[0]);
-    v[1] = _mm_max_pd(v[1], l.v[1]);
-    return *this;
-  }
-
-  inline void* operator new [] (size_t n)
-  {
-    return _mm_malloc(n, 16);
-  }
-
-  inline void operator delete [] (void* x)
-  {
-    if(x) _mm_free(x);
-  }
-
-  inline double operator [] (size_t i) const { return vs[i]; }
-  inline double& operator [] (size_t i) { return vs[i]; }
-
-  inline sse_meta_d4 operator + (const sse_meta_d4& other) const { return sse_meta_d4(_mm_add_pd(v[0], other.v[0]), _mm_add_pd(v[1], other.v[1])); }
-  inline sse_meta_d4 operator - (const sse_meta_d4& other) const { return sse_meta_d4(_mm_sub_pd(v[0], other.v[0]), _mm_sub_pd(v[1], other.v[1])); }
-  inline sse_meta_d4 operator * (const sse_meta_d4& other) const { return sse_meta_d4(_mm_mul_pd(v[0], other.v[0]), _mm_mul_pd(v[1], other.v[1])); }
-  inline sse_meta_d4 operator / (const sse_meta_d4& other) const { return sse_meta_d4(_mm_div_pd(v[0], other.v[0]), _mm_div_pd(v[1], other.v[1])); }
-  inline sse_meta_d4& operator += (const sse_meta_d4& other) { v[0] = _mm_add_pd(v[0], other.v[0]); v[1] = _mm_add_pd(v[1], other.v[1]); return *this; }
-  inline sse_meta_d4& operator -= (const sse_meta_d4& other) { v[0] = _mm_sub_pd(v[0], other.v[0]); v[1] = _mm_sub_pd(v[1], other.v[1]); return *this; }
-  inline sse_meta_d4& operator *= (const sse_meta_d4& other) { v[0] = _mm_mul_pd(v[0], other.v[0]); v[1] = _mm_mul_pd(v[1], other.v[1]); return *this; }
-  inline sse_meta_d4& operator /= (const sse_meta_d4& other) { v[0] = _mm_div_pd(v[0], other.v[0]); v[1] = _mm_div_pd(v[1], other.v[1]); return *this; }
-  inline sse_meta_d4 operator + (double t) const { register __m128d d = _mm_set1_pd(t); return sse_meta_d4(_mm_add_pd(v[0], d), _mm_add_pd(v[1], d)); }
-  inline sse_meta_d4 operator - (double t) const { register __m128d d = _mm_set1_pd(t); return sse_meta_d4(_mm_sub_pd(v[0], d), _mm_sub_pd(v[1], d)); }
-  inline sse_meta_d4 operator * (double t) const { register __m128d d = _mm_set1_pd(t); return sse_meta_d4(_mm_mul_pd(v[0], d), _mm_mul_pd(v[1], d)); }
-  inline sse_meta_d4 operator / (double t) const { register __m128d d = _mm_set1_pd(t); return sse_meta_d4(_mm_div_pd(v[0], d), _mm_div_pd(v[1], d)); }
-  inline sse_meta_d4& operator += (double t) { register __m128d d = _mm_set1_pd(t); v[0] = _mm_add_pd(v[0], d); v[1] = _mm_add_pd(v[1], d); return *this; }
-  inline sse_meta_d4& operator -= (double t) { register __m128d d = _mm_set1_pd(t); v[0] = _mm_sub_pd(v[0], d); v[1] = _mm_sub_pd(v[1], d); return *this; }
-  inline sse_meta_d4& operator *= (double t) { register __m128d d = _mm_set1_pd(t); v[0] = _mm_mul_pd(v[0], d); v[1] = _mm_mul_pd(v[1], d); return *this; }
-  inline sse_meta_d4& operator /= (double t) { register __m128d d = _mm_set1_pd(t); v[0] = _mm_div_pd(v[0], d); v[1] = _mm_div_pd(v[1], d); return *this; }
-  inline sse_meta_d4 operator - () const 
-  {
-    static const union { FCL_INT64 i[2]; __m128d m; } negativemask __attribute__ ((aligned(16))) = {{0x8000000000000000, 0x8000000000000000}};
-    return sse_meta_d4(_mm_xor_pd(v[0], negativemask.m), _mm_xor_pd(v[1], negativemask.m));
-  }
-} __attribute__ ((aligned (16)));
-
-
-
-static inline __m128 cross_prod(__m128 x, __m128 y)
-{
-  // set to a[1][2][0][3] , b[2][0][1][3]
-  // multiply
-  static const int s1 = _MM_SHUFFLE(3, 0, 2, 1);
-  static const int s2 = _MM_SHUFFLE(3, 1, 0, 2);
-  __m128 xa = _mm_mul_ps(_mm_shuffle_ps(x, x, s1), _mm_shuffle_ps(y, y, s2));
-
-  // set to a[2][0][1][3] , b[1][2][0][3]
-  // multiply
-  __m128 xb = _mm_mul_ps(_mm_shuffle_ps(x, x, s2), _mm_shuffle_ps(y, y, s1));
-
-  // subtract
-  return _mm_sub_ps(xa, xb);
-}
-
-static inline sse_meta_f4 cross_prod(const sse_meta_f4& x, const sse_meta_f4& y)
-{
-  return sse_meta_f4(cross_prod(x.v, y.v));
-}
-
-static inline void cross_prod(__m128d x0, __m128d x1, __m128d y0, __m128d y1, __m128d* z0, __m128d* z1)
-{
-  static const int s0 = _MM_SHUFFLE2(0, 0);
-  static const int s1 = _MM_SHUFFLE2(0, 1);
-  static const int s2 = _MM_SHUFFLE2(1, 0);
-  static const int s3 = _MM_SHUFFLE2(1, 1);  
-  __m128d xa1 = _mm_mul_pd(_mm_shuffle_pd(x0, x1, s1), _mm_shuffle_pd(y1, y0, s0));
-  __m128d ya1 = _mm_mul_pd(_mm_shuffle_pd(x0, x1, s2), _mm_shuffle_pd(y0, y1, s3));
-  
-  __m128d xa2 = _mm_mul_pd(_mm_shuffle_pd(x1, x0, s0), _mm_shuffle_pd(y0, y1, s1));
-  __m128d ya2 = _mm_mul_pd(_mm_shuffle_pd(x0, x1, s3), _mm_shuffle_pd(y0, y1, s2));
-
-  *z0 = _mm_sub_pd(xa1, xa2);
-  *z1 = _mm_sub_pd(ya1, ya2);
-}
-
-static inline sse_meta_d4 cross_prod(const sse_meta_d4& x, const sse_meta_d4& y)
-{
-  __m128d z0, z1;
-  cross_prod(x.v[0], x.v[1], y.v[0], y.v[1], &z0, &z1);
-  return sse_meta_d4(z0, z1);
-}
-
-
-static inline __m128 dot_prod3(__m128 x, __m128 y)
-{
-  register __m128 m = _mm_mul_ps(x, y);
-  return _mm_add_ps(_mm_shuffle_ps(m, m, _MM_SHUFFLE(0, 0, 0, 0)),
-                    _mm_add_ps(vec_splat(m, 1), vec_splat(m, 2)));
-}
-
-static inline float dot_prod3(const sse_meta_f4& x, const sse_meta_f4& y)
-{
-  return _mm_cvtss_f32(dot_prod3(x.v, y.v));
-}
-
-
-static inline __m128d dot_prod3(__m128d x0, __m128d x1, __m128d y0, __m128d y1)
-{
-  register __m128d m1 = _mm_mul_pd(x0, y0);
-  register __m128d m2 = _mm_mul_pd(x1, y1);
-  return _mm_add_pd(_mm_add_pd(vec_splatd(m1, 0), vec_splatd(m1, 1)), vec_splatd(m2, 0));
-}
-
-static inline double dot_prod3(const sse_meta_d4& x, const sse_meta_d4& y)
-{
-  double d;
-  _mm_storel_pd(&d, dot_prod3(x.v[0], x.v[1], y.v[0], y.v[1]));
-  return d;
-}
-
-static inline __m128 dot_prod4(__m128 x, __m128 y)
-{
-#if defined (__SSE4__)
-  return _mm_dp_ps(x, y, 0x71);
-#elif defined (__SSE3__)
-  register __m128 t = _mm_mul_ps(x, y);
-  t = _mm_hadd_ps(t, t);
-  return _mm_hadd_ps(t, t);
-#else
-  register __m128 s = _mm_mul_ps(x, y);
-  register __m128 r = _mm_add_ss(s, _mm_movehl_ps(s, s));
-  return _mm_add_ss(r, _mm_shuffle_ps(r, r, 1));
-#endif
-}
-
-
-static inline float dot_prod4(const sse_meta_f4& x, const sse_meta_f4& y)
-{
-  return _mm_cvtss_f32(dot_prod4(x.v, y.v));
-}
-
-static inline __m128d dot_prod4(__m128d x0, __m128d x1, __m128d y0, __m128d y1)
-{
-#if defined (__SSE4__)
-  register __m128d t1 = _mm_dp_pd(x0, y0, 0x31);
-  register __m128d t2 = _mm_dp_pd(x1, y1, 0x11);
-  return _mm_add_pd(t1, t2);
-#elif defined (__SSE3__)
-  register __m128d t1 = _mm_mul_pd(x0, y0);
-  register __m128d t2 = _mm_mul_pd(x1, y1);
-  t1 = _mm_hadd_pd(t1, t1);
-  t2 = _mm_hadd_pd(t2, t2);
-  return _mm_add_pd(t1, t2);
-#else 
-  register __m128d t1 = _mm_mul_pd(x0, y0);
-  register __m128d t2 = _mm_mul_pd(x1, y1);
-  t1 = _mm_add_pd(t1, t2);
-  return _mm_add_pd(t1, _mm_shuffle_pd(t1, t1, 1));
-#endif
-}
-
-static inline double dot_prod4(const sse_meta_d4& x, const sse_meta_d4& y)
-{
-  double d;
-  _mm_storel_pd(&d, dot_prod4(x.v[0], x.v[1], y.v[0], y.v[1]));
-  return d;
-}
-
-static inline sse_meta_f4 min(const sse_meta_f4& x, const sse_meta_f4& y)
-{
-  return sse_meta_f4(_mm_min_ps(x.v, y.v));
-}
-
-static inline sse_meta_d4 min(const sse_meta_d4& x, const sse_meta_d4& y)
-{
-  return sse_meta_d4(_mm_min_pd(x.v[0], y.v[0]), _mm_min_pd(x.v[1], y.v[1]));
-}
-
-static inline sse_meta_f4 max(const sse_meta_f4& x, const sse_meta_f4& y)
-{
-  return sse_meta_f4(_mm_max_ps(x.v, y.v));
-}
-
-static inline sse_meta_d4 max(const sse_meta_d4& x, const sse_meta_d4& y)
-{
-  return sse_meta_d4(_mm_max_pd(x.v[0], y.v[0]), _mm_max_pd(x.v[1], y.v[1]));
-}
-
-static inline sse_meta_f4 abs(const sse_meta_f4& x)
-{
-  static const union { int i[4]; __m128 m; } abs4mask __attribute__ ((aligned (16))) = {{0x7fffffff, 0x7fffffff, 0x7fffffff, 0x7fffffff}};
-  return sse_meta_f4(_mm_and_ps(x.v, abs4mask.m));
-}
-
-static inline sse_meta_d4 abs(const sse_meta_d4& x)
-{
-  static const union { FCL_INT64 i[2]; __m128d m; } abs2mask __attribute__ ((aligned (16))) = {{0x7fffffffffffffff, 0x7fffffffffffffff}};
-  return sse_meta_d4(_mm_and_pd(x.v[0], abs2mask.m), _mm_and_pd(x.v[1], abs2mask.m));
-}
-
-static inline bool equal(const sse_meta_f4& x, const sse_meta_f4& y, float epsilon)
-{
-  register __m128 d = _mm_sub_ps(x.v, y.v);
-  register __m128 e = _mm_set1_ps(epsilon);
-  return ((_mm_movemask_ps(_mm_cmplt_ps(d, e)) & 0x7) == 0x7) && ((_mm_movemask_ps(_mm_cmpgt_ps(d, _mm_sub_ps(xmms_0, e))) & 0x7) == 0x7);
-}
-
-static inline bool equal(const sse_meta_d4& x, const sse_meta_d4& y, double epsilon)
-{
-  register __m128d d = _mm_sub_pd(x.v[0], y.v[0]);
-  register __m128d e = _mm_set1_pd(epsilon);
-  
-  if(_mm_movemask_pd(_mm_cmplt_pd(d, e)) != 0x3) return false;
-  if(_mm_movemask_pd(_mm_cmpgt_pd(d, _mm_sub_pd(xmmd_0, e))) != 0x3) return false;
-  
-  d = _mm_sub_pd(x.v[1], y.v[1]);
-  if((_mm_movemask_pd(_mm_cmplt_pd(d, e)) & 0x1) != 0x1) return false;
-  if((_mm_movemask_pd(_mm_cmpgt_pd(d, _mm_sub_pd(xmmd_0, e))) & 0x1) != 0x1) return false;
-  return true;
-}
-
-static inline sse_meta_f4 normalize3(const sse_meta_f4& x)
-{
-  register __m128 m = _mm_mul_ps(x.v, x.v);
-  __m128 r = _mm_add_ps(vec_splat(m, 0), _mm_add_ps(vec_splat(m, 1), vec_splat(m, 2)));
-  return sse_meta_f4(_mm_mul_ps(x.v, newtonraphson_rsqrt4(r)));
-}
-
-static inline sse_meta_f4 normalize3_approx(const sse_meta_f4& x)
-{
-  register __m128 m = _mm_mul_ps(x.v, x.v);
-  __m128 r = _mm_add_ps(vec_splat(m, 0), _mm_add_ps(vec_splat(m, 1), vec_splat(m, 2)));
-  return sse_meta_f4(_mm_mul_ps(x.v, _mm_rsqrt_ps(r)));
-}
-
-
-static inline void transpose(__m128 c0, __m128 c1, __m128 c2, __m128* r0, __m128* r1, __m128* r2)
-{
-  static const union { unsigned int i[4]; __m128 m; } selectmask __attribute__ ((aligned(16))) = {{0, 0xffffffff, 0, 0}};
-  register __m128 t0, t1;
-  t0 = _mm_unpacklo_ps(c0, c2);
-  t1 = _mm_unpackhi_ps(c0, c2);
-  *r0 = _mm_unpacklo_ps(t0, c1);
-  *r1 = _mm_shuffle_ps(t0, t0, _MM_SHUFFLE(0, 3, 2, 2));
-  *r1 = vec_sel(*r1, c1, selectmask.i);
-  *r2 = _mm_shuffle_ps(t1, t1, _MM_SHUFFLE(0, 1, 1, 0));
-  *r2 = vec_sel(*r2, vec_splat(c1, 2), selectmask.i);
-}
-
-
-static inline void inverse(__m128 c0, __m128 c1, __m128 c2, __m128* i0, __m128* i1, __m128* i2)
-{
-  __m128 t0, t1, t2, d, invd;
-  t2 = cross_prod(c0, c1);
-  t0 = cross_prod(c1, c2);
-  t1 = cross_prod(c2, c0);
-  d = dot_prod3(t2, c2);
-  d = vec_splat(d, 0);
-  invd = _mm_rcp_ps(d); // approximate inverse
-  transpose(t0, t1, t2, i0, i1, i2);
-  *i0 = _mm_mul_ps(*i0, invd);
-  *i1 = _mm_mul_ps(*i1, invd);
-  *i2 = _mm_mul_ps(*i2, invd);
-}
-
-
-struct sse_meta_f12
-{
-  typedef float meta_type;
-  typedef sse_meta_f4 vector_type;
-  sse_meta_f4 c[3];
-
-  sse_meta_f12() { setZero(); }
-
-  sse_meta_f12(float xx, float xy, float xz,
-               float yx, float yy, float yz,
-               float zx, float zy, float zz)
-  { setValue(xx, xy, xz, yx, yy, yz, zx, zy, zz); }
-
-  sse_meta_f12(const sse_meta_f4& x, const sse_meta_f4& y, const sse_meta_f4& z)
-  { setColumn(x, y, z); }
-
-  sse_meta_f12(__m128 x, __m128 y, __m128 z)
-  { setColumn(x, y, z); }
-
-  inline void setValue(float xx, float xy, float xz,
-                       float yx, float yy, float yz,
-                       float zx, float zy, float zz)
-  {
-    c[0].setValue(xx, yx, zx, 0);
-    c[1].setValue(xy, yy, zy, 0);
-    c[2].setValue(xz, yz, zz, 0);
-  }
-
-  inline void setIdentity()
-  {
-    c[0].setValue(1, 0, 0, 0);
-    c[1].setValue(0, 1, 0, 0);
-    c[2].setValue(0, 0, 1, 0);
-  }
-
-  inline void setZero()
-  {
-    c[0].setValue(0);
-    c[1].setValue(0);
-    c[2].setValue(0);
-  }
-
-  inline void setColumn(const sse_meta_f4& x, const sse_meta_f4& y, const sse_meta_f4& z)
-  {
-    c[0] = x; c[1] = y; c[2] = z;
-  }
-
-  inline void setColumn(__m128 x, __m128 y, __m128 z)
-  {
-    c[0].setValue(x); c[1].setValue(y); c[2].setValue(z);
-  }
-
-  inline const sse_meta_f4& getColumn(size_t i) const
-  {
-    return c[i];
-  }
-
-  inline sse_meta_f4& getColumn(size_t i) 
-  {
-    return c[i];
-  }
-
-  inline sse_meta_f4 getRow(size_t i) const
-  {
-    return sse_meta_f4(c[0][i], c[1][i], c[2][i], 0);
-  }
-
-  inline float operator () (size_t i, size_t j) const
-  {
-    return c[j][i];
-  }
-
-  inline float& operator () (size_t i, size_t j) 
-  {
-    return c[j][i];
-  }
-
-  inline sse_meta_f4 operator * (const sse_meta_f4& v) const
-  {
-    return sse_meta_f4(_mm_add_ps(_mm_add_ps(_mm_mul_ps(c[0].v, vec_splat(v.v, 0)), _mm_mul_ps(c[1].v, vec_splat(v.v, 1))), _mm_mul_ps(c[2].v, vec_splat(v.v, 2))));
-  }
-
-  inline sse_meta_f12 operator * (const sse_meta_f12& mat) const
-  {
-    return sse_meta_f12((*this) * mat.c[0], (*this) * mat.c[1], (*this) * mat.c[2]);
-  }
-
-  inline sse_meta_f12 operator + (const sse_meta_f12& mat) const
-  {
-    return sse_meta_f12(c[0] + mat.c[0], c[1] + mat.c[1], c[2] + mat.c[2]);
-  }
-
-  inline sse_meta_f12 operator - (const sse_meta_f12& mat) const
-  {
-    return sse_meta_f12(c[0] - mat.c[0], c[1] - mat.c[1], c[2] - mat.c[2]);
-  }
-
-  inline sse_meta_f12 operator + (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f12(c[0] + t, c[1] + t, c[2] + t);
-  }
-
-  inline sse_meta_f12 operator - (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f12(c[0] - t, c[1] - t, c[2] - t);
-  }
-
-  inline sse_meta_f12 operator * (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f12(c[0] * t, c[1] * t, c[2] * t);
-  }
-
-  inline sse_meta_f12 operator / (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f12(c[0] / t, c[1] / t, c[2] / t);
-  }
-
-  inline sse_meta_f12& operator *= (const sse_meta_f12& mat)
-  {
-    setColumn((*this) * mat.c[0], (*this) * mat.c[1], (*this) * mat.c[2]);
-    return *this;
-  }
-
-  inline sse_meta_f12& operator += (const sse_meta_f12& mat)
-  {
-    c[0] += mat.c[0];
-    c[1] += mat.c[1];
-    c[2] += mat.c[2];
-    return *this;
-  }
-
-  inline sse_meta_f12& operator -= (const sse_meta_f12& mat)
-  {
-    c[0] -= mat.c[0];
-    c[1] -= mat.c[1];
-    c[2] -= mat.c[2];
-    return *this;
-  }
-
-  inline sse_meta_f12& operator += (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] += t;
-    c[1] += t;
-    c[2] += t;
-    return *this;
-  }
-
-  inline sse_meta_f12& operator -= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] -= t;
-    c[1] -= t;
-    c[2] -= t;
-    return *this;
-  }
-
-  inline sse_meta_f12& operator *= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] *= t;
-    c[1] *= t;
-    c[2] *= t;
-    return *this;
-  }
-
-  inline sse_meta_f12& operator /= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] /= t;
-    c[1] /= t;
-    c[2] /= t;
-    return *this;
-  }
-
-  inline sse_meta_f12& inverse()
-  {
-    __m128 inv0, inv1, inv2;
-    details::inverse(c[0].v, c[1].v, c[2].v, &inv0, &inv1, &inv2);
-    setColumn(inv0, inv1, inv2);
-    return *this;
-  }
-
-  inline sse_meta_f12& transpose()
-  {
-    __m128 r0, r1, r2;
-    details::transpose(c[0].v, c[1].v, c[2].v, &r0, &r1, &r2);
-    setColumn(r0, r1, r2);
-    return *this;
-  }
-
-  inline sse_meta_f12& abs()
-  {
-    c[0] = details::abs(c[0]);
-    c[1] = details::abs(c[1]);
-    c[2] = details::abs(c[2]);
-    return *this;
-  }
-
-  inline float determinant() const
-  {
-    return _mm_cvtss_f32(dot_prod3(c[2].v, cross_prod(c[0].v, c[1].v)));
-  }
-
-  inline sse_meta_f12 transposeTimes(const sse_meta_f12& other) const
-  {
-    return sse_meta_f12(dot_prod3(c[0], other.c[0]), dot_prod3(c[0], other.c[1]), dot_prod3(c[0], other.c[2]),
-                        dot_prod3(c[1], other.c[0]), dot_prod3(c[1], other.c[1]), dot_prod3(c[1], other.c[2]),
-                        dot_prod3(c[2], other.c[0]), dot_prod3(c[2], other.c[1]), dot_prod3(c[2], other.c[2]));
-  }
-
-  inline sse_meta_f12 timesTranspose(const sse_meta_f12& m) const
-  {
-    sse_meta_f12 tmp(m);
-    return (*this) * tmp.transpose();
-  }
-
-  inline sse_meta_f4 transposeTimes(const sse_meta_f4& v) const
-  {
-    return sse_meta_f4(dot_prod3(c[0], v), dot_prod3(c[1], v), dot_prod3(c[2], v));
-  }
-
-  inline float transposeDot(size_t i, const sse_meta_f4& v) const
-  {
-    return dot_prod3(c[i], v);
-  }
-
-  inline float dot(size_t i, const sse_meta_f4& v) const
-  {
-    return v[0] * c[0][i] + v[1] * c[1][i] + v[2] * c[2][i];
-  }
-
-};
-
-static inline sse_meta_f12 abs(const sse_meta_f12& mat)
-{
-  return sse_meta_f12(abs(mat.getColumn(0)), abs(mat.getColumn(1)), abs(mat.getColumn(2)));
-}
-
-static inline sse_meta_f12 transpose(const sse_meta_f12& mat)
-{
-  __m128 r0, r1, r2;
-  transpose(mat.getColumn(0).v, mat.getColumn(1).v, mat.getColumn(2).v, &r0, &r1, &r2);
-  return sse_meta_f12(r0, r1, r2);
-}
-
-
-static inline sse_meta_f12 inverse(const sse_meta_f12& mat)
-{
-  __m128 inv0, inv1, inv2;
-  inverse(mat.getColumn(0).v, mat.getColumn(1).v, mat.getColumn(2).v, &inv0, &inv1, &inv2);
-  return sse_meta_f12(inv0, inv1, inv2);
-}
-
-
-static inline void transpose(__m128 c0, __m128 c1, __m128 c2, __m128 c3,
-                             __m128* r0, __m128* r1, __m128* r2, __m128* r3)
-{
-  __m128 tmp0 = _mm_unpacklo_ps(c0, c2);
-  __m128 tmp1 = _mm_unpacklo_ps(c1, c3);
-  __m128 tmp2 = _mm_unpackhi_ps(c0, c2);
-  __m128 tmp3 = _mm_unpackhi_ps(c1, c3);
-  *r0 = _mm_unpacklo_ps(tmp0, tmp1);
-  *r1 = _mm_unpackhi_ps(tmp0, tmp1);
-  *r2 = _mm_unpacklo_ps(tmp2, tmp3);
-  *r3 = _mm_unpackhi_ps(tmp2, tmp3);
-}
-
-
-static inline void inverse(__m128 c0, __m128 c1, __m128 c2, __m128 c3,
-                           __m128* res0, __m128* res1, __m128* res2, __m128* res3)
-{
-  __m128 Va, Vb, Vc;
-  __m128 r1, r2, r3, tt, tt2;
-  __m128 sum, Det, RDet;
-  __m128 trns0, trns1, trns2, trns3;
-
-  // Calculating the minterms for the first line.
-
-  tt = c3; tt2 = _mm_ror_ps(c2,1); 
-  Vc = _mm_mul_ps(tt2,_mm_ror_ps(tt,0));					// V3'\B7V4
-  Va = _mm_mul_ps(tt2,_mm_ror_ps(tt,2));					// V3'\B7V4"
-  Vb = _mm_mul_ps(tt2,_mm_ror_ps(tt,3));					// V3'\B7V4^
-
-  r1 = _mm_sub_ps(_mm_ror_ps(Va,1),_mm_ror_ps(Vc,2));		// V3"\B7V4^ - V3^\B7V4"
-  r2 = _mm_sub_ps(_mm_ror_ps(Vb,2),_mm_ror_ps(Vb,0));		// V3^\B7V4' - V3'\B7V4^
-  r3 = _mm_sub_ps(_mm_ror_ps(Va,0),_mm_ror_ps(Vc,1));		// V3'\B7V4" - V3"\B7V4'
-
-  tt = c1;
-  Va = _mm_ror_ps(tt,1);		sum = _mm_mul_ps(Va,r1);
-  Vb = _mm_ror_ps(tt,2);		sum = _mm_add_ps(sum,_mm_mul_ps(Vb,r2));
-  Vc = _mm_ror_ps(tt,3);		sum = _mm_add_ps(sum,_mm_mul_ps(Vc,r3));
-
-  // Calculating the determinant.
-  Det = _mm_mul_ps(sum,c0);
-  Det = _mm_add_ps(Det,_mm_movehl_ps(Det,Det));
-
-  static const union { int i[4]; __m128 m; } Sign_PNPN __attribute__ ((aligned(16))) = {{0x00000000, 0x80000000, 0x00000000, 0x80000000}};
-  static const union { int i[4]; __m128 m; } Sign_NPNP __attribute__ ((aligned(16))) = {{0x80000000, 0x00000000, 0x80000000, 0x00000000}};
-  static const union { float i[4]; __m128 m; } ZERONE __attribute__ ((aligned(16))) = {{1.0f, 0.0f, 0.0f, 1.0f}};
-
-  __m128 mtL1 = _mm_xor_ps(sum,Sign_PNPN.m);
-
-  // Calculating the minterms of the second line (using previous results).
-  tt = _mm_ror_ps(c0,1);		sum = _mm_mul_ps(tt,r1);
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r2));
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r3));
-  __m128 mtL2 = _mm_xor_ps(sum,Sign_NPNP.m);
-
-  // Testing the determinant.
-  Det = _mm_sub_ss(Det,_mm_shuffle_ps(Det,Det,1));
-
-  // Calculating the minterms of the third line.
-  tt = _mm_ror_ps(c0,1);
-  Va = _mm_mul_ps(tt,Vb);									// V1'\B7V2"
-  Vb = _mm_mul_ps(tt,Vc);									// V1'\B7V2^
-  Vc = _mm_mul_ps(tt,c1);								// V1'\B7V2
-
-  r1 = _mm_sub_ps(_mm_ror_ps(Va,1),_mm_ror_ps(Vc,2));		// V1"\B7V2^ - V1^\B7V2"
-  r2 = _mm_sub_ps(_mm_ror_ps(Vb,2),_mm_ror_ps(Vb,0));		// V1^\B7V2' - V1'\B7V2^
-  r3 = _mm_sub_ps(_mm_ror_ps(Va,0),_mm_ror_ps(Vc,1));		// V1'\B7V2" - V1"\B7V2'
-
-  tt = _mm_ror_ps(c3,1);		sum = _mm_mul_ps(tt,r1);
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r2));
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r3));
-  __m128 mtL3 = _mm_xor_ps(sum,Sign_PNPN.m);
-
-  // Dividing is FASTER than rcp_nr! (Because rcp_nr causes many register-memory RWs).
-  RDet = _mm_div_ss(ZERONE.m, Det); // TODO: just 1.0f?
-  RDet = _mm_shuffle_ps(RDet,RDet,0x00);
-
-  // Devide the first 12 minterms with the determinant.
-  mtL1 = _mm_mul_ps(mtL1, RDet);
-  mtL2 = _mm_mul_ps(mtL2, RDet);
-  mtL3 = _mm_mul_ps(mtL3, RDet);
-
-  // Calculate the minterms of the forth line and devide by the determinant.
-  tt = _mm_ror_ps(c2,1);		sum = _mm_mul_ps(tt,r1);
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r2));
-  tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r3));
-  __m128 mtL4 = _mm_xor_ps(sum,Sign_NPNP.m);
-  mtL4 = _mm_mul_ps(mtL4, RDet);
-
-  // Now we just have to transpose the minterms matrix.
-  trns0 = _mm_unpacklo_ps(mtL1,mtL2);
-  trns1 = _mm_unpacklo_ps(mtL3,mtL4);
-  trns2 = _mm_unpackhi_ps(mtL1,mtL2);
-  trns3 = _mm_unpackhi_ps(mtL3,mtL4);
-  *res0 = _mm_movelh_ps(trns0,trns1);
-  *res1 = _mm_movehl_ps(trns1,trns0);
-  *res2 = _mm_movelh_ps(trns2,trns3);
-  *res3 = _mm_movehl_ps(trns3,trns2);
-}
-
-
-struct sse_meta_f16
-{
-  typedef float meta_type;
-  typedef sse_meta_f4 vector_type;
-  sse_meta_f4 c[4];
-
-  sse_meta_f16() { setZero(); }
-  
-  sse_meta_f16(float xx, float xy, float xz, float xw,
-               float yx, float yy, float yz, float yw,
-               float zx, float zy, float zz, float zw,
-               float wx, float wy, float wz, float ww)
-  { setValue(xx, xy, xz, xw, yz, yy, yz, yw, zx, zy, zz, zw, wx, wy, wz, ww); }
-
-  sse_meta_f16(const sse_meta_f4& x, const sse_meta_f4& y, const sse_meta_f4& z, const sse_meta_f4& w)
-  { setColumn(x, y, z, w); }
-
-  sse_meta_f16(__m128 x, __m128 y, __m128 z, __m128 w)
-  { setColumn(x, y, z, w); }
-
-  inline void setValue(float xx, float xy, float xz, float xw,
-                       float yx, float yy, float yz, float yw,
-                       float zx, float zy, float zz, float zw,
-                       float wx, float wy, float wz, float ww)
-  {
-    c[0].setValue(xx, yx, zx, wx);
-    c[1].setValue(xy, yy, zy, wy);
-    c[2].setValue(xz, yz, zz, wz);
-    c[3].setValue(xw, yw, zw, ww);
-  }
-
-  inline void setColumn(const sse_meta_f4& x, const sse_meta_f4& y, const sse_meta_f4& z, const sse_meta_f4& w)
-  {
-    c[0] = x; c[1] = y; c[2] = z; c[3] = w;
-  }
-
-  inline void setColumn(__m128 x, __m128 y, __m128 z, __m128 w)
-  {
-    c[0].setValue(x); c[1].setValue(y); c[2].setValue(z); c[3].setValue(w);
-  }
-
-  inline void setIdentity()
-  {
-    c[0].setValue(1, 0, 0, 0);
-    c[1].setValue(0, 1, 0, 0);
-    c[2].setValue(0, 0, 1, 0);
-    c[3].setValue(0, 0, 0, 1);
-  }
-
-  inline void setZero()
-  {
-    c[0].setValue(0);
-    c[1].setValue(0);
-    c[2].setValue(0);
-    c[3].setValue(0);
-  }
-
-  inline const sse_meta_f4& getColumn(size_t i) const
-  {
-    return c[i];
-  }
-
-  inline sse_meta_f4& getColumn(size_t i) 
-  {
-    return c[i];
-  }
-
-  inline sse_meta_f4 getRow(size_t i) const
-  {
-    return sse_meta_f4(c[0][i], c[1][i], c[2][i], c[3][i]);
-  }
-
-  inline float operator () (size_t i, size_t j) const
-  {
-    return c[j][i];
-  }
-
-  inline float& operator () (size_t i, size_t j) 
-  {
-    return c[j][i];
-  }
-
-  inline sse_meta_f4 operator * (const sse_meta_f4& v) const
-  {
-    return sse_meta_f4(_mm_add_ps(_mm_add_ps(_mm_mul_ps(c[0].v, vec_splat(v.v, 0)), _mm_mul_ps(c[1].v, vec_splat(v.v, 1))), 
-                                  _mm_add_ps(_mm_mul_ps(c[2].v, vec_splat(v.v, 2)), _mm_mul_ps(c[3].v, vec_splat(v.v, 3)))
-                                  ));
-  }
-
-  inline sse_meta_f16 operator * (const sse_meta_f16& mat) const
-  {
-    return sse_meta_f16((*this) * mat.c[0], (*this) * mat.c[1], (*this) * mat.c[2], (*this) * mat.c[3]);
-  }
-
-
-  inline sse_meta_f16 operator + (const sse_meta_f16& mat) const
-  {
-    return sse_meta_f16(c[0] + mat.c[0], c[1] + mat.c[1], c[2] + mat.c[2], c[3] + mat.c[3]);
-  }
-
-  inline sse_meta_f16 operator - (const sse_meta_f16& mat) const
-  {
-    return sse_meta_f16(c[0] - mat.c[0], c[1] - mat.c[1], c[2] - mat.c[2], c[3] - mat.c[3]);
-  }
-
-  inline sse_meta_f16 operator + (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f16(c[0] + t, c[1] + t, c[2] + t, c[3] + t);
-  }
-
-  inline sse_meta_f16 operator - (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f16(c[0] - t, c[1] - t, c[2] - t, c[3] - t);
-  }
-
-  inline sse_meta_f16 operator * (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f16(c[0] * t, c[1] * t, c[2] * t, c[3] * t);
-  }
-
-  inline sse_meta_f16 operator / (float t_) const
-  {
-    sse_meta_f4 t(t_);
-    return sse_meta_f16(c[0] / t, c[1] / t, c[2] / t, c[3] / t);
-  }
-
-  inline sse_meta_f16& operator *= (const sse_meta_f16& mat)
-  {
-    setColumn((*this) * mat.c[0], (*this) * mat.c[1], (*this) * mat.c[2], (*this) * mat.c[3]);
-    return *this;
-  }
-
-  inline sse_meta_f16& operator += (const sse_meta_f16& mat)
-  {
-    c[0] += mat.c[0];
-    c[1] += mat.c[1];
-    c[2] += mat.c[2];
-    c[3] += mat.c[3];
-    return *this;
-  }
-
-  inline sse_meta_f16& operator -= (const sse_meta_f16& mat)
-  {
-    c[0] -= mat.c[0];
-    c[1] -= mat.c[1];
-    c[2] -= mat.c[2];
-    c[3] -= mat.c[3];
-    return *this;
-  }
-
-  inline sse_meta_f16& operator += (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] += t;
-    c[1] += t;
-    c[2] += t;
-    c[3] += t;
-    return *this;
-  }
-
-  inline sse_meta_f16& operator -= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] -= t;
-    c[1] -= t;
-    c[2] -= t;
-    c[3] -= t;
-    return *this;
-  }
-
-  inline sse_meta_f16& operator *= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] *= t;
-    c[1] *= t;
-    c[2] *= t;
-    c[3] *= t;
-    return *this;
-  }
-
-  inline sse_meta_f16& operator /= (float t_)
-  {
-    sse_meta_f4 t(t_);
-    c[0] /= t;
-    c[1] /= t;
-    c[2] /= t;
-    c[3] /= t;
-    return *this;
-  }
-
-  inline sse_meta_f16& abs()
-  {
-    c[0] = details::abs(c[0]);
-    c[1] = details::abs(c[1]);
-    c[2] = details::abs(c[2]);
-    c[3] = details::abs(c[3]);
-    return *this;
-  }
-
-  inline sse_meta_f16& inverse() 
-  {
-    __m128 r0, r1, r2, r3;
-    details::inverse(c[0].v, c[1].v, c[2].v, c[3].v, &r0, &r1, &r2, &r3);
-    setColumn(r0, r1, r2, r3);
-    return *this;
-  }
-
-  inline sse_meta_f16& transpose() 
-  {
-    __m128 r0, r1, r2, r3;
-    details::transpose(c[0].v, c[1].v, c[2].v, c[3].v, &r0, &r1, &r2, &r3);
-    setColumn(r0, r1, r2, r3);
-    return *this;
-  }
-
-  inline float determinant() const
-  {
-    __m128 Va, Vb, Vc;
-    __m128 r1, r2, r3, tt, tt2;
-    __m128 sum, Det;
-
-    __m128 _L1 = c[0].v;
-    __m128 _L2 = c[1].v;
-    __m128 _L3 = c[2].v;
-    __m128 _L4 = c[3].v;
-    // Calculating the minterms for the first line.
-
-    // _mm_ror_ps is just a macro using _mm_shuffle_ps().
-    tt = _L4; tt2 = _mm_ror_ps(_L3,1); 
-    Vc = _mm_mul_ps(tt2,_mm_ror_ps(tt,0));					// V3'·V4
-    Va = _mm_mul_ps(tt2,_mm_ror_ps(tt,2));					// V3'·V4"
-    Vb = _mm_mul_ps(tt2,_mm_ror_ps(tt,3));					// V3'·V4^
-
-    r1 = _mm_sub_ps(_mm_ror_ps(Va,1),_mm_ror_ps(Vc,2));		// V3"·V4^ - V3^·V4"
-    r2 = _mm_sub_ps(_mm_ror_ps(Vb,2),_mm_ror_ps(Vb,0));		// V3^·V4' - V3'·V4^
-    r3 = _mm_sub_ps(_mm_ror_ps(Va,0),_mm_ror_ps(Vc,1));		// V3'·V4" - V3"·V4'
-
-    tt = _L2;
-    Va = _mm_ror_ps(tt,1);		sum = _mm_mul_ps(Va,r1);
-    Vb = _mm_ror_ps(tt,2);		sum = _mm_add_ps(sum,_mm_mul_ps(Vb,r2));
-    Vc = _mm_ror_ps(tt,3);		sum = _mm_add_ps(sum,_mm_mul_ps(Vc,r3));
-
-    // Calculating the determinant.
-    Det = _mm_mul_ps(sum,_L1);
-    Det = _mm_add_ps(Det,_mm_movehl_ps(Det,Det));
-
-    // Calculating the minterms of the second line (using previous results).
-    tt = _mm_ror_ps(_L1,1);		sum = _mm_mul_ps(tt,r1);
-    tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r2));
-    tt = _mm_ror_ps(tt,1);		sum = _mm_add_ps(sum,_mm_mul_ps(tt,r3));
-
-    // Testing the determinant.
-    Det = _mm_sub_ss(Det,_mm_shuffle_ps(Det,Det,1));
-    return _mm_cvtss_f32(Det);
-  }
-
-  inline sse_meta_f16 transposeTimes(const sse_meta_f16& other) const
-  {
-    return sse_meta_f16(dot_prod4(c[0], other.c[0]), dot_prod4(c[0], other.c[1]), dot_prod4(c[0], other.c[2]), dot_prod4(c[0], other.c[3]),
-                        dot_prod4(c[1], other.c[0]), dot_prod4(c[1], other.c[1]), dot_prod4(c[1], other.c[2]), dot_prod4(c[1], other.c[3]),
-                        dot_prod4(c[2], other.c[0]), dot_prod4(c[2], other.c[1]), dot_prod4(c[2], other.c[2]), dot_prod4(c[2], other.c[3]),
-                        dot_prod4(c[3], other.c[0]), dot_prod4(c[3], other.c[1]), dot_prod4(c[3], other.c[2]), dot_prod4(c[3], other.c[3]));
-  }
-
-  inline sse_meta_f16 timesTranspose(const sse_meta_f16& m) const
-  {
-    sse_meta_f16 tmp(m);
-    return (*this) * tmp.transpose();
-  }
-
-  inline sse_meta_f4 transposeTimes(const sse_meta_f4& v) const
-  {
-    return sse_meta_f4(dot_prod4(c[0], v), dot_prod4(c[1], v), dot_prod4(c[2], v), dot_prod4(c[3], v));
-  }
-
-  inline float transposeDot(size_t i, const sse_meta_f4& v) const
-  {
-    return dot_prod4(c[i], v);
-  }
-
-  inline float dot(size_t i, const sse_meta_f4& v) const
-  {
-    return v[0] * c[0][i] + v[1] * c[1][i] + v[2] * c[2][i] + v[3] * c[3][i];
-  }
-
-};
-
-static inline sse_meta_f16 abs(const sse_meta_f16& mat)
-{
-  return sse_meta_f16(abs(mat.getColumn(0)), abs(mat.getColumn(1)), abs(mat.getColumn(2)), abs(mat.getColumn(3)));
-}
-
-static inline sse_meta_f16 transpose(const sse_meta_f16& mat)
-{
-  __m128 r0, r1, r2, r3;
-  transpose(mat.getColumn(0).v, mat.getColumn(1).v, mat.getColumn(2).v, mat.getColumn(3).v, &r0, &r1, &r2, &r3);
-  return sse_meta_f16(r0, r1, r2, r3);
-}
-
-
-static inline sse_meta_f16 inverse(const sse_meta_f16& mat)
-{
-  __m128 r0, r1, r2, r3;
-  inverse(mat.getColumn(0).v, mat.getColumn(1).v, mat.getColumn(2).v, mat.getColumn(3).v, &r0, &r1, &r2, &r3);
-  return sse_meta_f16(r0, r1, r2, r3);
-}
-
-                                
-
-
-} // details
-} // fcl
-
-
-#endif
diff --git a/include/hpp/fcl/simd/simd_intersect.h b/include/hpp/fcl/simd/simd_intersect.h
deleted file mode 100644
index 1e94e8e5..00000000
--- a/include/hpp/fcl/simd/simd_intersect.h
+++ /dev/null
@@ -1,243 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011-2014, Willow Garage, Inc.
- *  Copyright (c) 2014-2015, Open Source Robotics Foundation
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Open Source Robotics Foundation nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-/** \author Jia Pan */
-
-#ifndef FCL_MULTIPLE_INTERSECT
-#define FCL_MULTIPLE_INTERSECT
-
-#include <hpp/fcl/math/vec_3f.h>
-
-#include <xmmintrin.h>
-#include <pmmintrin.h>
-
-
-namespace fcl
-{
-
-
-static inline __m128 sse_four_spheres_intersect(const Vec3f& o1, FCL_REAL r1,
-                                                const Vec3f& o2, FCL_REAL r2,
-                                                const Vec3f& o3, FCL_REAL r3,
-                                                const Vec3f& o4, FCL_REAL r4,
-                                                const Vec3f& o5, FCL_REAL r5,
-                                                const Vec3f& o6, FCL_REAL r6,
-                                                const Vec3f& o7, FCL_REAL r7,
-                                                const Vec3f& o8, FCL_REAL r8)
-{
-  __m128 PX, PY, PZ, PR, QX, QY, QZ, QR;
-  PX = _mm_set_ps(o1[0], o2[0], o3[0], o4[0]);
-  PY = _mm_set_ps(o1[1], o2[1], o3[1], o4[1]);
-  PZ = _mm_set_ps(o1[2], o2[2], o3[2], o4[2]);
-  PR = _mm_set_ps(r1, r2, r3, r4);
-  QX = _mm_set_ps(o5[0], o6[0], o7[0], o8[0]);
-  QY = _mm_set_ps(o5[1], o6[1], o7[1], o8[1]);
-  QZ = _mm_set_ps(o5[2], o6[2], o7[2], o8[2]);
-  QR = _mm_set_ps(r5, r6, r7, r8);
-
-  __m128 T1 = _mm_sub_ps(PX, QX);
-  __m128 T2 = _mm_sub_ps(PY, QY);
-  __m128 T3 = _mm_sub_ps(PZ, QZ);
-  __m128 T4 = _mm_add_ps(PR, QR);
-  T1 = _mm_mul_ps(T1, T1);
-  T2 = _mm_mul_ps(T2, T2);
-  T3 = _mm_mul_ps(T3, T3);
-  T4 = _mm_mul_ps(T4, T4);
-  T1 = _mm_add_ps(T1, T2);
-  T2 = _mm_sub_ps(R2, T3);
-  return _mm_cmple_ps(T1, T2);
-}
-
-
-static inline __m128 sse_four_spheres_four_AABBs_intersect(const Vec3f& o1, FCL_REAL r1,
-                                                           const Vec3f& o2, FCL_REAL r2,
-                                                           const Vec3f& o3, FCL_REAL r3,
-                                                           const Vec3f& o4, FCL_REAL r4,
-                                                           const Vec3f& min1, const Vec3f& max1,
-                                                           const Vec3f& min2, const Vec3f& max2,
-                                                           const Vec3f& min3, const Vec3f& max3,
-                                                           const Vec3f& min4, const Vec3f& max4)
-{
-  __m128 MINX, MINY, MINZ, MAXX, MAXX, MAXY, MAXZ, SX, SY, SZ, SR;
-  MINX = _mm_set_ps(min1[0], min2[0], min3[0], min4[0]);
-  MAXX = _mm_set_ps(max1[0], max2[0], max3[0], max4[0]);
-  MINY = _mm_set_ps(min1[1], min2[1], min3[1], min4[1]);
-  MAXY = _mm_set_ps(max1[1], max2[1], max3[1], max4[1]);
-  MINZ = _mm_set_ps(min1[2], min2[2], min3[2], min4[2]);
-  MAXZ = _mm_set_ps(max1[2], max2[2], max3[2], max4[2]);
-  SX = _mm_set_ps(o1[0], o2[0], o3[0], o4[0]);
-  SY = _mm_set_ps(o1[1], o2[1], o3[1], o4[1]);
-  SZ = _mm_set_ps(o1[2], o2[2], o3[2], o4[2]);
-  SR = _mm_set_ps(r1, r2, r3, r4);
-
-
-  __m128 TX = _mm_max_ps(SX, MINX);
-  __m128 TY = _mm_max_ps(SY, MINY);
-  __m128 TZ = _mm_max_ps(SZ, MINZ);
-  TX = _mm_min_ps(TX, MAXX);
-  TY = _mm_min_ps(TY, MAXY);
-  TZ = _mm_min_ps(TZ, MAXZ);
-  __m128 DX = _mm_sub_ps(SX, TX);
-  __m128 DY = _mm_sub_ps(SY, TY);
-  __m128 DZ = _mm_sub_ps(SZ, TZ);
-  __m128 R2 = _mm_mul_ps(SR, SR);
-  DX = _mm_mul_ps(DX, DX);
-  DY = _mm_mul_ps(DY, DY);
-  DZ = _mm_mul_ps(DZ, DZ);
-  __m128 T1 = _mm_add_ps(DX, DY);
-  __m128 T2 = _mm_sub_ps(R2, DZ);
-  return _mm_cmple_ps(T1, T2);  
-}
-
-
-static inline __m128 sse_four_AABBs_intersect(const Vec3f& min1, const Vec3f& max1,
-                                              const Vec3f& min2, const Vec3f& max2,
-                                              const Vec3f& min3, const Vec3f& max3,
-                                              const Vec3f& min4, const Vec3f& max4,
-                                              const Vec3f& min5, const Vec3f& max5,
-                                              const Vec3f& min6, const Vec3f& max6,
-                                              const Vec3f& min7, const Vec3f& max7,
-                                              const Vec3f& min8, const Vec3f& max8)
-{
-  __m128 MIN1X, MIN1Y, MIN1Z, MAX1X, MAX1Y, MAX1Z, MIN2X, MIN2Y, MIN2Z, MAX2X, MAX2Y, MAX2Z;
-  MIN1X = _mm_set_ps(min1[0], min2[0], min3[0], min4[0]);
-  MAX1X = _mm_set_ps(max1[0], max2[0], max3[0], max4[0]);
-  MIN1Y = _mm_set_ps(min1[1], min2[1], min3[1], min4[1]);
-  MAX1Y = _mm_set_ps(max1[1], max2[1], max3[1], max4[1]);
-  MIN1Z = _mm_set_ps(min1[2], min2[2], min3[2], min4[2]);
-  MAX1Z = _mm_set_ps(max1[2], max2[2], max3[2], max4[2]);
-  MIN2X = _mm_set_ps(min5[0], min6[0], min7[0], min8[0]);
-  MAX2X = _mm_set_ps(max5[0], max6[0], max7[0], max8[0]);
-  MIN2Y = _mm_set_ps(min5[1], min6[1], min7[1], min8[1]);
-  MAX2Y = _mm_set_ps(max5[1], max6[1], max7[1], max8[1]);
-  MIN2Z = _mm_set_ps(min5[2], min6[2], min7[2], min8[2]);
-  MAX2Z = _mm_set_ps(max5[2], max6[2], max7[2], max8[2]);
-
-  __m128 AX = _mm_max_ps(MIN1X, MIN2X);
-  __m128 BX = _mm_min_ps(MAX1X, MAX2X);
-  __m128 AY = _mm_max_ps(MIN1Y, MIN2Y);
-  __m128 BY = _mm_min_ps(MAX1Y, MAX2Y);
-  __m128 AZ = _mm_max_ps(MIN1Z, MIN2Z);
-  __m128 BZ = _mm_min_ps(MAX1Z, MAX2Z);
-  __m128 T1 = _mm_cmple_ps(AX, BX);
-  __m128 T2 = _mm_cmple_ps(AY, BY);
-  __m128 T3 = _mm_cmple_ps(AZ, BZ);
-  __m128 T4 = _mm_and_ps(T1, T2);
-  return _mm_and_ps(T3, T4);
-}
-
-static bool four_spheres_intersect_and(const Vec3f& o1, FCL_REAL r1,
-                                       const Vec3f& o2, FCL_REAL r2,
-                                       const Vec3f& o3, FCL_REAL r3,
-                                       const Vec3f& o4, FCL_REAL r4,
-                                       const Vec3f& o5, FCL_REAL r5,
-                                       const Vec3f& o6, FCL_REAL r6,
-                                       const Vec3f& o7, FCL_REAL r7,
-                                       const Vec3f& o8, FCL_REAL r8)
-{
-  __m128 CMP = four_spheres_intersect(o1, r1, o2, r2, o3, r3, o4, r4, o5, r5, o6, r6, o7, r7, o8, r8);
-  return _mm_movemask_ps(CMP) == 15.f;
-}
-
-static bool four_spheres_intersect_or(const Vec3f& o1, FCL_REAL r1,
-                                      const Vec3f& o2, FCL_REAL r2,
-                                      const Vec3f& o3, FCL_REAL r3,
-                                      const Vec3f& o4, FCL_REAL r4,
-                                      const Vec3f& o5, FCL_REAL r5,
-                                      const Vec3f& o6, FCL_REAL r6,
-                                      const Vec3f& o7, FCL_REAL r7,
-                                      const Vec3f& o8, FCL_REAL r8)
-{
-  __m128 CMP = four_spheres_intersect(o1, r1, o2, r2, o3, r3, o4, r4, o5, r5, o6, r6, o7, r7, o8, r8);
-  return __mm_movemask_ps(CMP) > 0;
-}
-
-/** \brief four spheres versus four AABBs SIMD test */
-static bool four_spheres_four_AABBs_intersect_and(const Vec3f& o1, FCL_REAL r1,
-                                                  const Vec3f& o2, FCL_REAL r2,
-                                                  const Vec3f& o3, FCL_REAL r3,
-                                                  const Vec3f& o4, FCL_REAL r4,
-                                                  const Vec3f& min1, const Vec3f& max1,
-                                                  const Vec3f& min2, const Vec3f& max2,
-                                                  const Vec3f& min3, const Vec3f& max3,
-                                                  const Vec3f& min4, const Vec3f& max4)
-{
-  __m128 CMP = four_spheres_four_AABBs_intersect(o1, r1, o2, r2, o3, r3, o4, r4, min1, max1, min2, max2, min3, max3, min4, max4);
-  return _mm_movemask_ps(CMP) == 15.f;
-}
-
-static bool four_spheres_four_AABBs_intersect_or(const Vec3f& o1, FCL_REAL r1,
-                                                 const Vec3f& o2, FCL_REAL r2,
-                                                 const Vec3f& o3, FCL_REAL r3,
-                                                 const Vec3f& o4, FCL_REAL r4,
-                                                 const Vec3f& min1, const Vec3f& max1,
-                                                 const Vec3f& min2, const Vec3f& max2,
-                                                 const Vec3f& min3, const Vec3f& max3,
-                                                 const Vec3f& min4, const Vec3f& max4)
-{
-  __m128 CMP = four_spheres_four_AABBs_intersect(o1, r1, o2, r2, o3, r3, o4, r4, min1, max1, min2, max2, min3, max3, min4, max4);
-  return _mm_movemask_ps(CMP) > 0;
-}
-
-/** \brief four AABBs versus four AABBs SIMD test */
-static bool four_AABBs_intersect_and(const Vec3f& min1, const Vec3f& max1,
-                                     const Vec3f& min2, const Vec3f& max2,
-                                     const Vec3f& min3, const Vec3f& max3,
-                                     const Vec3f& min4, const Vec3f& max4,
-                                     const Vec3f& min5, const Vec3f& max5,
-                                     const Vec3f& min6, const Vec3f& max6,
-                                     const Vec3f& min7, const Vec3f& max7,
-                                     const Vec3f& min8, const Vec3f& max8)
-{
-  __m128 CMP = four_AABBs_intersect(min1, max1, min2, max2, min3, max3, min4, max4, min5, max5, min6, max6, min7, max7, min8, max8);
-  return _mm_movemask_ps(CMP) == 15.f;
-}
-
-static bool four_AABBs_intersect_or(const Vec3f& min1, const Vec3f& max1,
-                                    const Vec3f& min2, const Vec3f& max2,
-                                    const Vec3f& min3, const Vec3f& max3,
-                                    const Vec3f& min4, const Vec3f& max4,
-                                    const Vec3f& min5, const Vec3f& max5,
-                                    const Vec3f& min6, const Vec3f& max6,
-                                    const Vec3f& min7, const Vec3f& max7,
-                                    const Vec3f& min8, const Vec3f& max8)
-{
-  __m128 CMP = four_AABBs_intersect(min1, max1, min2, max2, min3, max3, min4, max4, min5, max5, min6, max6, min7, max7, min8, max8);
-  return _mm_movemask_ps(CMP) > 0;
-}
-
-}
-
-#endif
-- 
GitLab