diff --git a/CMakeLists.txt b/CMakeLists.txt
index 39e6d55d96f32dba6ec7f84a084b5f8e9c3c2cc2..d0a563a67cc399948e83761b27552fea7e6d2725 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -59,6 +59,7 @@ include(cmake/python.cmake)
 include(cmake/hpp.cmake)
 include(cmake/apple.cmake)
 include(cmake/ide.cmake)
+include(cmake/test.cmake)
 
 # If needed, fix CMake policy for APPLE systems
 APPLY_DEFAULT_APPLE_CONFIGURATION()
@@ -75,11 +76,11 @@ if (BUILD_PYTHON_INTERFACE)
 endif ()
 
 # Add a cache variable to allow not compiling and running tests
-set (RUN_TESTS TRUE CACHE BOOL "compile and run unit tests")
+set (BUILD_TESTING TRUE CACHE BOOL "compile and run unit tests")
 
 # Required dependencies
 set(BOOST_COMPONENTS thread date_time system)
-if (RUN_TESTS)
+if (BUILD_TESTING)
   set(BOOST_COMPONENTS ${BOOST_COMPONENTS} filesystem unit_test_framework chrono)
 endif ()
 if (BUILD_PYTHON_INTERFACE)
@@ -156,9 +157,7 @@ add_subdirectory(src)
 if (BUILD_PYTHON_INTERFACE)
   add_subdirectory(python)
 endif ()
-if (RUN_TESTS)
-  add_subdirectory(test)
-endif ()
+add_subdirectory(test)
 
 pkg_config_append_libs("hpp-fcl")
 PKG_CONFIG_APPEND_BOOST_LIBS(thread date_time filesystem system)
diff --git a/doc/Doxyfile.extra.in b/doc/Doxyfile.extra.in
index 27c2d816eb3f2d09ea6e166c0b7523edc80f76b2..16c2c547b955dd182889e191dba47249f0ec6b49 100644
--- a/doc/Doxyfile.extra.in
+++ b/doc/Doxyfile.extra.in
@@ -1,3 +1 @@
 FILE_PATTERNS          = *.h  *.hh  *.hxx
-
-GENERATE_TREEVIEW      = NO
diff --git a/doc/distance_computation.png b/doc/distance_computation.png
new file mode 100644
index 0000000000000000000000000000000000000000..783b3bb1b99c594f9fd7761ad7b21264f04ae356
Binary files /dev/null and b/doc/distance_computation.png differ
diff --git a/doc/generate_distance_plot.py b/doc/generate_distance_plot.py
new file mode 100644
index 0000000000000000000000000000000000000000..f5260de367ba2064d129ba0dbb78ad82feef20a7
--- /dev/null
+++ b/doc/generate_distance_plot.py
@@ -0,0 +1,54 @@
+import matplotlib.pyplot as plt
+import numpy as np
+from math import sqrt
+
+interactive = False
+
+m = 1.
+b = 1.2
+
+mb = m+b
+
+X = np.array([ -mb/2, 0, m, mb, 2*mb ])
+#X = np.linspace(-1, 4., 21)
+
+def dlb(d):
+    if d<0: return None
+    if d > mb:
+        u = d-mb
+        return mb-m + u / 2
+    return d-m
+
+plt.figure(figsize=(9, 3.5))
+#plt.plot(X, X-m, ":k")
+#plt.plot([m+b, X[-1]], [b, b], ":k")
+plt.fill_between([m+b, X[-1]], [b, b], [b, X[-1]-m], alpha=0.2, hatch="|", facecolor="g", label="Distance lower band area")
+plt.plot(X, [ dlb(x) for x in X ], "-g", label="distance lower bound")
+#plt.plot([X[0], m, m, X[-1]], [0, 0, b, b], ":k")
+plt.axvspan(X[0], m, alpha=0.5, hatch="\\", facecolor="r", label="Collision area")
+
+
+ax = plt.gca()
+ax.set_xlabel("Object distance")
+ax.set_xticks([0, m, mb])
+ax.set_xticklabels(["0", "security margin", "security margin\n+ break distance"])
+ax.set_yticks([0, b])
+ax.set_yticklabels(["0", "break distance"])
+ax.grid(which="major", ls="solid")
+ax.grid(which="minor", ls="dashed")
+
+plt.axvline(0, ls="solid")
+#plt.axvline(m, ls="dashed", label="margin")
+#plt.axvline(mb, ls="dashed")
+plt.axhline(0., ls="solid")
+
+plt.title("Collision and distance lower band")
+plt.legend(loc="lower right")
+if interactive:
+    plt.show()
+else:
+    import os.path as path
+    dir_path = path.dirname(path.realpath(__file__))
+    plt.savefig(path.join(dir_path, "distance_computation.png"),
+            bbox_inches="tight",
+            orientation="landscape")
diff --git a/include/hpp/fcl/BV/AABB.h b/include/hpp/fcl/BV/AABB.h
index 9b1ed094f4b39bed4f75dc6d261d020be16b2a81..96681d0f689c3ab92b70eab8ab353fdc0749a056 100644
--- a/include/hpp/fcl/BV/AABB.h
+++ b/include/hpp/fcl/BV/AABB.h
@@ -47,8 +47,8 @@ namespace fcl
 
 struct CollisionRequest;
 
-/// @defgroup Bounding_Volume 
-/// regroup class of differents types of bounding volume.
+/// @defgroup Bounding_Volume Bounding volumes
+/// Classes of different types of bounding volume.
 /// @{
 
 /// @brief A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points
@@ -114,7 +114,7 @@ public:
     return true;
   }    
 
-  /// Not implemented
+  /// @brief Check whether two AABB are overlap
   bool overlap(const AABB& other, const CollisionRequest& request,
                FCL_REAL& sqrDistLowerBound) const;
 
diff --git a/include/hpp/fcl/BV/BV_node.h b/include/hpp/fcl/BV/BV_node.h
index 901a9fcb1f6d9035200a165d99af10fbaf7b4a6a..13e681278872efd0fa6459c8ccfc7c7ef7d3e7c8 100644
--- a/include/hpp/fcl/BV/BV_node.h
+++ b/include/hpp/fcl/BV/BV_node.h
@@ -49,8 +49,8 @@ namespace hpp
 namespace fcl
 {
 
-/// @defgroup Construction_Of_BVH 
-/// regroup class which are used to build BVH (Bounding Volume Hierarchy)
+/// @defgroup Construction_Of_BVH Construction of BVHModel
+/// Classes which are used to build a BVHModel (Bounding Volume Hierarchy)
 /// @{
 
 /// @brief BVNodeBase encodes the tree structure for BVH
diff --git a/include/hpp/fcl/BV/OBBRSS.h b/include/hpp/fcl/BV/OBBRSS.h
index e7ef5c7edfb926eebe896d343a2126ba9bf66835..cc3ff2a03e1056294fbc9669891d4e641ae648ca 100644
--- a/include/hpp/fcl/BV/OBBRSS.h
+++ b/include/hpp/fcl/BV/OBBRSS.h
@@ -158,9 +158,10 @@ inline bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBBRSS& b1, const
 }
 
 /// Check collision between two OBBRSS
+/// @param  R0, T0 configuration of b1
 /// @param  b1 first OBBRSS in configuration (R0, T0)
 /// @param  b2 second OBBRSS in identity position
-/// @retval squared lower bound on the distance if OBBRSS do not overlap.
+/// @retval sqrDistLowerBound squared lower bound on the distance if OBBRSS do not overlap.
 inline bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBBRSS& b1,
                     const OBBRSS& b2, const CollisionRequest& request,
 	            FCL_REAL& sqrDistLowerBound)
diff --git a/include/hpp/fcl/BVH/BVH_model.h b/include/hpp/fcl/BVH/BVH_model.h
index 095ff21c250877fb5b5c42a94aa0b6a89d7b3756..16383a2edf217cfd5e14ec0d4fb0b34547381ee1 100644
--- a/include/hpp/fcl/BVH/BVH_model.h
+++ b/include/hpp/fcl/BVH/BVH_model.h
@@ -250,6 +250,7 @@ protected:
 };
 
 /// @brief A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh)
+/// \tparam BV one of the bounding volume class in \ref Bounding_Volume.
 template<typename BV>
 class BVHModel : public BVHModelBase
 {
diff --git a/include/hpp/fcl/collision_data.h b/include/hpp/fcl/collision_data.h
index db61106193549b0d2af496c562fe01dd42ed2782..a39c709a0b5e5a5242ecf7123c40fc4d46246fa0 100644
--- a/include/hpp/fcl/collision_data.h
+++ b/include/hpp/fcl/collision_data.h
@@ -39,21 +39,21 @@
 #ifndef HPP_FCL_COLLISION_DATA_H
 #define HPP_FCL_COLLISION_DATA_H
 
-#include <hpp/fcl/collision_object.h>
-
-#include <hpp/fcl/data_types.h>
 #include <vector>
 #include <set>
 #include <limits>
 
+#include <hpp/fcl/collision_object.h>
+#include <hpp/fcl/config.hh>
+#include <hpp/fcl/data_types.h>
+
 
 namespace hpp
 {
 namespace fcl
 {
 
-/// @brief Type of narrow phase GJK solver
-enum GJKSolverType {GST_INDEP};
+const int GST_INDEP HPP_FCL_DEPRECATED = 0;
 
 /// @brief Contact information returned by collision
 struct Contact
@@ -158,19 +158,18 @@ struct CollisionRequest
   /// Whether a lower bound on distance is returned when objects are disjoint
   bool enable_distance_lower_bound;
 
-  /// @brief narrow phase solver
-  GJKSolverType gjk_solver_type;
-
   /// @brief whether enable gjk intial guess
   bool enable_cached_gjk_guess;
   
   /// @brief the gjk intial guess set by user
   Vec3f cached_gjk_guess;
 
-  /// @brief Distance below which objects are considered in collision
+  /// @brief Distance below which objects are considered in collision.
+  /// See \ref hpp_fcl_collision_and_distance_lower_bound_computation
   FCL_REAL security_margin;
 
-  /// @brief Distance below which bounding volumes are break down
+  /// @brief Distance below which bounding volumes are broken down.
+  /// See \ref hpp_fcl_collision_and_distance_lower_bound_computation
   FCL_REAL break_distance;
 
   explicit CollisionRequest(size_t num_max_contacts_,
@@ -178,15 +177,13 @@ struct CollisionRequest
 		   bool enable_distance_lower_bound_ = false,
                    size_t num_max_cost_sources_ = 1,
                    bool enable_cost_ = false,
-                   bool use_approximate_cost_ = true,
-                   GJKSolverType gjk_solver_type_ = GST_INDEP)
+                   bool use_approximate_cost_ = true)
   HPP_FCL_DEPRECATED;
 
   explicit CollisionRequest(const CollisionRequestFlag flag, size_t num_max_contacts_) :
     num_max_contacts(num_max_contacts_),
     enable_contact(flag & CONTACT),
     enable_distance_lower_bound (flag & DISTANCE_LOWER_BOUND),
-    gjk_solver_type(GST_INDEP),
     security_margin (0),
     break_distance (1e-3)
   {
@@ -198,7 +195,6 @@ struct CollisionRequest
       num_max_contacts(1),
       enable_contact(false),
       enable_distance_lower_bound (false),
-      gjk_solver_type(GST_INDEP),
       security_margin (0),
       break_distance (1e-3)
     {
@@ -219,8 +215,10 @@ private:
 public:
   Vec3f cached_gjk_guess;
 
-  /// Lower bound on distance between objects if they are disjoint
-  /// @note computed only on request.
+  /// Lower bound on distance between objects if they are disjoint.
+  /// See \ref hpp_fcl_collision_and_distance_lower_bound_computation
+  /// @note computed only on request (or if it does not add any computational
+  /// overhead).
   FCL_REAL distance_lower_bound;
 
 public:
@@ -294,18 +292,23 @@ struct DistanceRequest
   FCL_REAL rel_err; // relative error, between 0 and 1
   FCL_REAL abs_err; // absoluate error
 
-  /// @brief narrow phase solver type
-  GJKSolverType gjk_solver_type;
-
-
+  /// \deprecated the last argument should be removed.
+  DistanceRequest(bool enable_nearest_points_,
+                  FCL_REAL rel_err_,
+                  FCL_REAL abs_err_,
+                  int /*unused*/) HPP_FCL_DEPRECATED :
+    enable_nearest_points(enable_nearest_points_),
+    rel_err(rel_err_),
+    abs_err(abs_err_)
+  {
+  }
 
   DistanceRequest(bool enable_nearest_points_ = false,
                   FCL_REAL rel_err_ = 0.0,
-                  FCL_REAL abs_err_ = 0.0,
-                  GJKSolverType gjk_solver_type_ = GST_INDEP) : enable_nearest_points(enable_nearest_points_),
-                                                                rel_err(rel_err_),
-                                                                abs_err(abs_err_),
-                                                                gjk_solver_type(gjk_solver_type_)
+                  FCL_REAL abs_err_ = 0.0) :
+    enable_nearest_points(enable_nearest_points_),
+    rel_err(rel_err_),
+    abs_err(abs_err_)
   {
   }
 
diff --git a/include/hpp/fcl/data_types.h b/include/hpp/fcl/data_types.h
index 3d3c3beab99fbb660b46e55b09fa37d4e47f2616..2af6ec255001264383b23ff5c5674e25d2b65840 100644
--- a/include/hpp/fcl/data_types.h
+++ b/include/hpp/fcl/data_types.h
@@ -95,7 +95,7 @@ public:
     vids[0] = p1; vids[1] = p2; vids[2] = p3;
   }
 
-  /// @access the triangle index
+  /// @brief Access the triangle index
   inline index_type operator[](int i) const { return vids[i]; }
 
   inline index_type& operator[](int i) { return vids[i]; }
diff --git a/include/hpp/fcl/doc.hh b/include/hpp/fcl/doc.hh
index a5442cefd3695ed8d8069e0b3b4084b44efa2342..1f972b5b1f941f2216b38877d2e8dd4dd80812f5 100644
--- a/include/hpp/fcl/doc.hh
+++ b/include/hpp/fcl/doc.hh
@@ -32,10 +32,15 @@
 //  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 //  POSSIBILITY OF SUCH DAMAGE.
 
+namespace hpp
+{
+namespace fcl
+{
+
 /// \mainpage
 /// \anchor hpp_fcl_documentation
 ///
-/// \par Introduction
+/// \section hpp_fcl_introduction Introduction
 ///
 /// hpp-fcl is a modified version the FCL libraries.
 ///
@@ -47,5 +52,24 @@
 /// \par Using hpp-fcl
 ///
 /// The main entry points to the library are functions
-/// \li hpp::fcl::collide and
-/// \li hpp::fcl::distance.
+/// \li hpp::fcl::collide(const CollisionObject*, const CollisionObject*, const CollisionRequest&, CollisionResult&)
+/// \li hpp::fcl::distance(const CollisionObject*, const CollisionObject*, const DistanceRequest&, DistanceResult&)
+///
+/// \section hpp_fcl_collision_and_distance_lower_bound_computation Collision detection and distance lower bound
+///
+/// Collision queries can return a distance lower bound between the two objects,
+/// which is computationally cheaper than computing the real distance.
+/// The following figure shows the returned result in
+/// CollisionResult::distance_lower_bound and DistanceResult::min_distance,
+/// with respect to the objects real distance.
+///
+/// \image html doc/distance_computation.png
+///
+/// The two parameters refer to CollisionRequest::security_margin and
+/// CollisionRequest::break_distance.
+/// \note In the green hatched area, the distance lower bound is not known. It
+/// is only guaranted that it will be inferior to
+/// <em>distance - security_margin</em> and superior to \em break_distance.
+
+} // namespace fcl
+} // namespace hpp
diff --git a/include/hpp/fcl/internal/tools.h b/include/hpp/fcl/internal/tools.h
index e8c89a1dde94f91fa6e34ca6b499e93ef156feba..0b4db2311565fe60c005ea839c2628b83b6b45be 100644
--- a/include/hpp/fcl/internal/tools.h
+++ b/include/hpp/fcl/internal/tools.h
@@ -38,9 +38,6 @@
 #ifndef HPP_FCL_MATH_TOOLS_H
 #define HPP_FCL_MATH_TOOLS_H
 
-#include <hpp/fcl/deprecated.hh>
-#include <hpp/fcl/config.hh>
-
 #include <Eigen/Dense>
 #include <Eigen/Geometry>
 
@@ -48,6 +45,10 @@
 #include <iostream>
 #include <limits>
 
+#include <hpp/fcl/deprecated.hh>
+#include <hpp/fcl/config.hh>
+#include <hpp/fcl/data_types.h>
+
 namespace hpp
 {
 namespace fcl
diff --git a/include/hpp/fcl/internal/traversal_node_base.h b/include/hpp/fcl/internal/traversal_node_base.h
index 8c5fcadb5befdda376cd37ffd9eb16d437498174..441df058576a2032c4f8667b4107776c1ecb4b53 100644
--- a/include/hpp/fcl/internal/traversal_node_base.h
+++ b/include/hpp/fcl/internal/traversal_node_base.h
@@ -54,41 +54,46 @@ namespace fcl
 class TraversalNodeBase
 {
 public:
-  virtual ~TraversalNodeBase();
+  TraversalNodeBase () : enable_statistics(false) {}
+
+  virtual ~TraversalNodeBase() {}
 
   virtual void preprocess() {}
   
   virtual void postprocess() {}
 
   /// @brief Whether b is a leaf node in the first BVH tree 
-  virtual bool isFirstNodeLeaf(int b) const;
+  virtual bool isFirstNodeLeaf(int /*b*/) const { return true; }
 
   /// @brief Whether b is a leaf node in the second BVH tree
-  virtual bool isSecondNodeLeaf(int b) const;
+  virtual bool isSecondNodeLeaf(int /*b*/) const { return true; }
 
   /// @brief Traverse the subtree of the node in the first tree first
-  virtual bool firstOverSecond(int b1, int b2) const;
+  virtual bool firstOverSecond(int /*b1*/, int /*b2*/) const { return true; }
 
   /// @brief Get the left child of the node b in the first tree
-  virtual int getFirstLeftChild(int b) const;
+  virtual int getFirstLeftChild(int b) const { return b; }
 
   /// @brief Get the right child of the node b in the first tree
-  virtual int getFirstRightChild(int b) const;
+  virtual int getFirstRightChild(int b) const { return b; }
 
   /// @brief Get the left child of the node b in the second tree
-  virtual int getSecondLeftChild(int b) const;
+  virtual int getSecondLeftChild(int b) const { return b; }
 
   /// @brief Get the right child of the node b in the second tree
-  virtual int getSecondRightChild(int b) const;
+  virtual int getSecondRightChild(int b) const { return b; }
 
-  /// @brief Enable statistics (verbose mode)
-  virtual void enableStatistics(bool enable) = 0;
+  /// @brief Whether store some statistics information during traversal
+  void enableStatistics(bool enable) { enable_statistics = enable; }
 
   /// @brief configuation of first object
   Transform3f tf1;
 
   /// @brief configuration of second object
   Transform3f tf2;
+
+  /// @brief Whether stores statistics
+  bool enable_statistics;
 };
 
 /// @defgroup Traversal_For_Collision
@@ -100,9 +105,9 @@ class CollisionTraversalNodeBase : public TraversalNodeBase
 {
 public:
   CollisionTraversalNodeBase (const CollisionRequest& request_) :
-  request (request_), result(NULL), enable_statistics(false) {}
+  request (request_), result(NULL) {}
 
-  virtual ~CollisionTraversalNodeBase();
+  virtual ~CollisionTraversalNodeBase() {}
 
   /// @brief BV test between b1 and b2
   virtual bool BVDisjoints(int b1, int b2) const = 0;
@@ -120,10 +125,7 @@ public:
   }
 
   /// @brief Check whether the traversal can stop
-  virtual bool canStop() const;
-
-  /// @brief Whether store some statistics information during traversal
-  void enableStatistics(bool enable) { enable_statistics = enable; }
+  bool canStop() const { return this->request.isSatisfied(*(this->result)); }
 
   /// @brief request setting for collision
   const CollisionRequest& request;
@@ -145,32 +147,30 @@ public:
 class DistanceTraversalNodeBase : public TraversalNodeBase
 {
 public:
-  DistanceTraversalNodeBase() : result(NULL), enable_statistics(false) {}
+  DistanceTraversalNodeBase() : result(NULL) {}
 
-  virtual ~DistanceTraversalNodeBase();
+  virtual ~DistanceTraversalNodeBase() {}
 
   /// @brief BV test between b1 and b2
   /// @return a lower bound of the distance between the two BV.
   /// @note except for OBB, this method returns the distance.
-  virtual FCL_REAL BVDistanceLowerBound(int b1, int b2) const;
+  virtual FCL_REAL BVDistanceLowerBound(int /*b1*/, int /*b2*/) const
+  {
+    return std::numeric_limits<FCL_REAL>::max();
+  }
 
   /// @brief Leaf test between node b1 and b2, if they are both leafs
   virtual void leafComputeDistance(int b1, int b2) const = 0;
 
   /// @brief Check whether the traversal can stop
-  virtual bool canStop(FCL_REAL c) const;
-
-  /// @brief Whether store some statistics information during traversal
-  void enableStatistics(bool enable) { enable_statistics = enable; }
+  virtual bool canStop(FCL_REAL /*c*/) const
+  { return false; }
 
   /// @brief request setting for distance
   DistanceRequest request;
 
   /// @brief distance result kept during the traversal iteration
   DistanceResult* result;
-
-  /// @brief Whether stores statistics 
-  bool enable_statistics;
 };
 
 ///@}
diff --git a/include/hpp/fcl/internal/traversal_node_bvh_shape.h b/include/hpp/fcl/internal/traversal_node_bvh_shape.h
index 37162e5cadfe3837e7f8a2020580a2406b0b3beb..3613874ba2d1b417624ee950ab988ef6e0f23e30 100644
--- a/include/hpp/fcl/internal/traversal_node_bvh_shape.h
+++ b/include/hpp/fcl/internal/traversal_node_bvh_shape.h
@@ -253,65 +253,12 @@ public:
     assert (!this->result->isCollision () || sqrDistLowerBound > 0);
   }
 
-  /// @brief Whether the traversal process can stop early
-  bool canStop() const
-  {
-    return this->request.isSatisfied(*(this->result));
-  }
-
   Vec3f* vertices;
   Triangle* tri_indices;
 
   const GJKSolver* nsolver;
 };
 
-/// @brief Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)
-template<typename S>
-class MeshShapeCollisionTraversalNodeOBB : public MeshShapeCollisionTraversalNode<OBB, S, 0>
-{
-public:
-  MeshShapeCollisionTraversalNodeOBB(const CollisionRequest& request) :
-  MeshShapeCollisionTraversalNode<OBB, S, 0>
-    (request)
-  {
-  }
-
-};
-
-template<typename S>
-class MeshShapeCollisionTraversalNodeRSS : public MeshShapeCollisionTraversalNode<RSS, S, 0>
-{
-public:
-  MeshShapeCollisionTraversalNodeRSS (const CollisionRequest& request):
-  MeshShapeCollisionTraversalNode<RSS, S, 0>
-    (request)
-  {
-  }
-};
-
-template<typename S>
-class MeshShapeCollisionTraversalNodekIOS : public MeshShapeCollisionTraversalNode<kIOS, S, 0>
-{
-public:
-  MeshShapeCollisionTraversalNodekIOS(const CollisionRequest& request):
-  MeshShapeCollisionTraversalNode<kIOS, S, 0>
-    (request)
-  {
-  }
-};
-
-template<typename S>
-class MeshShapeCollisionTraversalNodeOBBRSS : public MeshShapeCollisionTraversalNode<OBBRSS, S, 0>
-{
-public:
-  MeshShapeCollisionTraversalNodeOBBRSS (const CollisionRequest& request) :
-  MeshShapeCollisionTraversalNode <OBBRSS, S, 0>
-    (request)
-  {
-  }
-};
-
-
 /// @brief Traversal node for collision between shape and mesh
 template<typename S, typename BV,
   int _Options = RelativeTransformationIsIdentity>
@@ -413,58 +360,12 @@ public:
     assert (!this->result->isCollision () || sqrDistLowerBound > 0);
   }
 
-  /// @brief Whether the traversal process can stop early
-  bool canStop() const
-  {
-    return this->request.isSatisfied(*(this->result));
-  }
-
   Vec3f* vertices;
   Triangle* tri_indices;
 
   const GJKSolver* nsolver;
 };
 
-/// @brief Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)
-template<typename S>
-class ShapeMeshCollisionTraversalNodeOBB : public ShapeMeshCollisionTraversalNode<S, OBB, 0>
-{
-public:
-  ShapeMeshCollisionTraversalNodeOBB() : ShapeMeshCollisionTraversalNode<S, OBB>()
-  {
-  }
-};
-
-
-template<typename S>
-class ShapeMeshCollisionTraversalNodeRSS : public ShapeMeshCollisionTraversalNode<S, RSS, 0>
-{
-public:
-  ShapeMeshCollisionTraversalNodeRSS() : ShapeMeshCollisionTraversalNode<S, RSS>()
-  {
-  }
-};
-
-
-template<typename S>
-class ShapeMeshCollisionTraversalNodekIOS : public ShapeMeshCollisionTraversalNode<S, kIOS, 0>
-{
-public:
-  ShapeMeshCollisionTraversalNodekIOS() : ShapeMeshCollisionTraversalNode<S, kIOS>()
-  {
-  }
-};
-
-
-template<typename S>
-class ShapeMeshCollisionTraversalNodeOBBRSS : public ShapeMeshCollisionTraversalNode<S, OBBRSS, 0>
-{
-public:
-  ShapeMeshCollisionTraversalNodeOBBRSS() : ShapeMeshCollisionTraversalNode<S, OBBRSS>()
-  {
-  }
-};
-
 /// @}
 
 /// @addtogroup Traversal_For_Distance
diff --git a/include/hpp/fcl/internal/traversal_node_bvhs.h b/include/hpp/fcl/internal/traversal_node_bvhs.h
index ed251b832357a59cc260229c818f2130101286b7..4c35a542ebcac90e994f93928f8f3fa6a7b1f34f 100644
--- a/include/hpp/fcl/internal/traversal_node_bvhs.h
+++ b/include/hpp/fcl/internal/traversal_node_bvhs.h
@@ -252,12 +252,6 @@ public:
     }
   }
 
-  /// @brief Whether the traversal process can stop early
-  bool canStop() const
-  {
-    return this->request.isSatisfied(*(this->result));
-  }
-
   Vec3f* vertices1;
   Vec3f* vertices2;
 
@@ -283,6 +277,10 @@ namespace details
     {
       return b1.distance(b2);
     }
+    static FCL_REAL run(const Matrix3f& R, const Vec3f& T, const BVNode<BV>& b1, const BVNode<BV>& b2)
+    {
+      return distance(R, T, b1.bv, b2.bv);
+    }
   };
 
   template<> struct DistanceTraversalBVDistanceLowerBound_impl<OBB>
@@ -298,6 +296,43 @@ namespace details
       }
       return sqrt (sqrDistLowerBound);
     }
+    static FCL_REAL run(const Matrix3f& R, const Vec3f& T, const BVNode<OBB>& b1, const BVNode<OBB>& b2)
+    {
+      FCL_REAL sqrDistLowerBound;
+      CollisionRequest request (DISTANCE_LOWER_BOUND, 0);
+      // request.break_distance = ?
+      if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
+        // TODO A penetration upper bound should be computed.
+        return -1;
+      }
+      return sqrt (sqrDistLowerBound);
+    }
+  };
+
+  template<> struct DistanceTraversalBVDistanceLowerBound_impl<AABB>
+  {
+    static FCL_REAL run(const BVNode<AABB>& b1, const BVNode<AABB>& b2)
+    {
+      FCL_REAL sqrDistLowerBound;
+      CollisionRequest request (DISTANCE_LOWER_BOUND, 0);
+      // request.break_distance = ?
+      if (b1.overlap(b2, request, sqrDistLowerBound)) {
+        // TODO A penetration upper bound should be computed.
+        return -1;
+      }
+      return sqrt (sqrDistLowerBound);
+    }
+    static FCL_REAL run(const Matrix3f& R, const Vec3f& T, const BVNode<AABB>& b1, const BVNode<AABB>& b2)
+    {
+      FCL_REAL sqrDistLowerBound;
+      CollisionRequest request (DISTANCE_LOWER_BOUND, 0);
+      // request.break_distance = ?
+      if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
+        // TODO A penetration upper bound should be computed.
+        return -1;
+      }
+      return sqrt (sqrDistLowerBound);
+    }
   };
 } // namespace details
 
@@ -369,14 +404,6 @@ public:
     return model2->getBV(b).rightChild();
   }
 
-  /// @brief BV culling test in one BVTT node
-  FCL_REAL BVDistanceLowerBound(int b1, int b2) const
-  {
-    if(enable_statistics) num_bv_tests++;
-    return details::DistanceTraversalBVDistanceLowerBound_impl<BV>
-      ::run (model1->getBV(b1), model2->getBV(b2));
-  }
-
   /// @brief The first BVH model
   const BVHModel<BV>* model1;
   /// @brief The second BVH model
@@ -390,10 +417,24 @@ public:
 
 
 /// @brief Traversal node for distance computation between two meshes
-template<typename BV>
+template<typename BV, int _Options = RelativeTransformationIsIdentity>
 class MeshDistanceTraversalNode : public BVHDistanceTraversalNode<BV>
 {
 public:
+  enum {
+    Options = _Options,
+    RTIsIdentity = _Options & RelativeTransformationIsIdentity
+  };
+
+  using BVHDistanceTraversalNode<BV>::enable_statistics;
+  using BVHDistanceTraversalNode<BV>::request;
+  using BVHDistanceTraversalNode<BV>::result;
+  using BVHDistanceTraversalNode<BV>::tf1;
+  using BVHDistanceTraversalNode<BV>::model1;
+  using BVHDistanceTraversalNode<BV>::model2;
+  using BVHDistanceTraversalNode<BV>::num_bv_tests;
+  using BVHDistanceTraversalNode<BV>::num_leaf_tests;
+
   MeshDistanceTraversalNode() : BVHDistanceTraversalNode<BV>()
   {
     vertices1 = NULL;
@@ -405,6 +446,28 @@ public:
     abs_err = this->request.abs_err;
   }
 
+  void preprocess()
+  {
+    if(!RTIsIdentity) preprocessOrientedNode();
+  }
+
+  void postprocess()
+  {
+    if(!RTIsIdentity) postprocessOrientedNode();
+  }
+
+  /// @brief BV culling test in one BVTT node
+  FCL_REAL BVDistanceLowerBound(int b1, int b2) const
+  {
+    if(enable_statistics) num_bv_tests++;
+    if (RTIsIdentity)
+      return details::DistanceTraversalBVDistanceLowerBound_impl<BV>
+        ::run (model1->getBV(b1), model2->getBV(b2));
+    else
+      return details::DistanceTraversalBVDistanceLowerBound_impl<BV>
+        ::run (RT._R(), RT._T(), model1->getBV(b1), model2->getBV(b2));
+  }
+
   /// @brief Distance testing between leaves (two triangles)
   void leafComputeDistance(int b1, int b2) const
   {
@@ -430,8 +493,15 @@ public:
     // nearest point pair
     Vec3f P1, P2, normal;
 
-    FCL_REAL d = sqrt (TriangleDistance::sqrTriDistance
-		       (t11, t12, t13, t21, t22, t23, P1, P2));
+    FCL_REAL d2;
+    if (RTIsIdentity)
+      d2 = TriangleDistance::sqrTriDistance (t11, t12, t13, t21, t22, t23,
+          P1, P2);
+    else
+      d2 = TriangleDistance::sqrTriDistance (t11, t12, t13, t21, t22, t23,
+          RT._R(), RT._T(),
+          P1, P2);
+    FCL_REAL d = sqrt(d2);
 
     this->result->update(d, this->model1, this->model2, primitive_id1,
                          primitive_id2, P1, P2, normal);
@@ -454,62 +524,52 @@ public:
   /// @brief relative and absolute error, default value is 0.01 for both terms
   FCL_REAL rel_err;
   FCL_REAL abs_err;
-};
 
-/// @brief Traversal node for distance computation between two meshes if their underlying BVH node is oriented node (RSS, OBBRSS, kIOS)
-class MeshDistanceTraversalNodeRSS : public MeshDistanceTraversalNode<RSS>
-{
-public:
-  MeshDistanceTraversalNodeRSS();
-
-  void preprocess();
-
-  void postprocess();
-
-  FCL_REAL BVDistanceLowerBound(int b1, int b2) const;
-
-  void leafComputeDistance(int b1, int b2) const;
-
-  Matrix3f R;
-  Vec3f T;
-};
-
-
-class MeshDistanceTraversalNodekIOS : public MeshDistanceTraversalNode<kIOS>
-{
-public:
-  MeshDistanceTraversalNodekIOS();
-
-  void preprocess();
-  
-  void postprocess();
-
-  FCL_REAL BVDistanceLowerBound(int b1, int b2) const;
-
-  void leafComputeDistance(int b1, int b2) const;
+  details::RelativeTransformation<!bool(RTIsIdentity)> RT;
 
-  Matrix3f R;
-  Vec3f T;
+private:
+  void preprocessOrientedNode()
+  {
+    const int init_tri_id1 = 0, init_tri_id2 = 0;
+    const Triangle& init_tri1 = tri_indices1[init_tri_id1];
+    const Triangle& init_tri2 = tri_indices2[init_tri_id2];
+
+    Vec3f init_tri1_points[3];
+    Vec3f init_tri2_points[3];
+
+    init_tri1_points[0] = vertices1[init_tri1[0]];
+    init_tri1_points[1] = vertices1[init_tri1[1]];
+    init_tri1_points[2] = vertices1[init_tri1[2]];
+
+    init_tri2_points[0] = vertices2[init_tri2[0]];
+    init_tri2_points[1] = vertices2[init_tri2[1]];
+    init_tri2_points[2] = vertices2[init_tri2[2]];
+
+    Vec3f p1, p2, normal;
+    FCL_REAL distance = sqrt (TriangleDistance::sqrTriDistance
+        (init_tri1_points[0], init_tri1_points[1],
+         init_tri1_points[2], init_tri2_points[0],
+         init_tri2_points[1], init_tri2_points[2],
+         RT._R(), RT._T(), p1, p2));
+
+    result->update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2,
+        normal);
+  }
+  void postprocessOrientedNode()
+  {
+    /// the points obtained by triDistance are not in world space: both are in object1's local coordinate system, so we need to convert them into the world space.
+    if(request.enable_nearest_points && (result->o1 == model1) && (result->o2 == model2))
+    {
+      result->nearest_points[0] = tf1.transform(result->nearest_points[0]);
+      result->nearest_points[1] = tf1.transform(result->nearest_points[1]);
+    }
+  }
 };
 
-class MeshDistanceTraversalNodeOBBRSS : public MeshDistanceTraversalNode<OBBRSS>
-{
-public:
-  MeshDistanceTraversalNodeOBBRSS();
-
-  void preprocess();
-
-  void postprocess();
-
-  FCL_REAL BVDistanceLowerBound(int b1, int b2) const;
-
-  FCL_REAL BVDistanceLowerBound(int b1, int b2, FCL_REAL& sqrDistLowerBound) const;
-
-  void leafComputeDistance(int b1, int b2) const;
-
-  Matrix3f R;
-  Vec3f T;
-};
+/// @brief Traversal node for distance computation between two meshes if their underlying BVH node is oriented node (RSS, OBBRSS, kIOS)
+typedef MeshDistanceTraversalNode<RSS   , 0> MeshDistanceTraversalNodeRSS;
+typedef MeshDistanceTraversalNode<kIOS  , 0> MeshDistanceTraversalNodekIOS;
+typedef MeshDistanceTraversalNode<OBBRSS, 0> MeshDistanceTraversalNodeOBBRSS;
 
 /// @}
 
diff --git a/include/hpp/fcl/internal/traversal_node_setup.h b/include/hpp/fcl/internal/traversal_node_setup.h
index 7a5006d134177e29c8c9b762615d2285eff97186..cb52eb800a7545e97f3889a996174f7c4c2359c3 100644
--- a/include/hpp/fcl/internal/traversal_node_setup.h
+++ b/include/hpp/fcl/internal/traversal_node_setup.h
@@ -40,6 +40,7 @@
 
 /// @cond INTERNAL
 
+#include <hpp/fcl/internal/tools.h>
 #include <hpp/fcl/internal/traversal_node_bvhs.h>
 #include <hpp/fcl/internal/traversal_node_shapes.h>
 #include <hpp/fcl/internal/traversal_node_bvh_shape.h>
@@ -342,16 +343,13 @@ bool initialize(MeshShapeCollisionTraversalNode<BV, S>& node,
   return true;
 }
 
-/// @cond IGNORE
-namespace details
-{
-
-template<typename BV, typename S, template<typename> class OrientedNode>
-static inline bool setupMeshShapeCollisionOrientedNode(OrientedNode<S>& node, 
-                                                       const BVHModel<BV>& model1, const Transform3f& tf1,
-                                                       const S& model2, const Transform3f& tf2,
-                                                       const GJKSolver* nsolver,
-                                                       CollisionResult& result)
+/// @brief Initialize traversal node for collision between one mesh and one shape
+template<typename BV, typename S>
+bool initialize(MeshShapeCollisionTraversalNode<BV, S, 0>& node,
+                const BVHModel<BV>& model1, const Transform3f& tf1,
+                const S& model2, const Transform3f& tf2,
+                const GJKSolver* nsolver,
+                CollisionResult& result)
 {
   if(model1.getModelType() != BVH_MODEL_TRIANGLES)
     return false;
@@ -372,56 +370,6 @@ static inline bool setupMeshShapeCollisionOrientedNode(OrientedNode<S>& node,
   return true;
 }
 
-}
-/// @endcond
-
-
-
-/// @brief Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type
-template<typename S>
-bool initialize(MeshShapeCollisionTraversalNodeOBB<S>& node,
-                const BVHModel<OBB>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
-                const GJKSolver* nsolver,
-                CollisionResult& result)
-{
-  return details::setupMeshShapeCollisionOrientedNode(node, model1, tf1, model2, tf2, nsolver, result);
-}
-
-/// @brief Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type
-template<typename S>
-bool initialize(MeshShapeCollisionTraversalNodeRSS<S>& node,
-                const BVHModel<RSS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
-                const GJKSolver* nsolver,
-                CollisionResult& result)
-{
-  return details::setupMeshShapeCollisionOrientedNode(node, model1, tf1, model2, tf2, nsolver, result);
-}
-
-/// @brief Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type
-template<typename S>
-bool initialize(MeshShapeCollisionTraversalNodekIOS<S>& node,
-                const BVHModel<kIOS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
-                const GJKSolver* nsolver,
-                CollisionResult& result)
-{
-  return details::setupMeshShapeCollisionOrientedNode(node, model1, tf1, model2, tf2, nsolver, result);
-}
-
-/// @brief Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type
-template<typename S>
-bool initialize(MeshShapeCollisionTraversalNodeOBBRSS<S>& node,
-                const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
-                const GJKSolver* nsolver,
-                CollisionResult& result)
-{
-  return details::setupMeshShapeCollisionOrientedNode(node, model1, tf1, model2, tf2, nsolver, result);
-}
-
-
 /// @cond IGNORE
 namespace details
 {
@@ -566,7 +514,7 @@ bool initialize(ShapeDistanceTraversalNode<S1, S2>& node,
 
 /// @brief Initialize traversal node for distance computation between two meshes, given the current transforms
 template<typename BV>
-bool initialize(MeshDistanceTraversalNode<BV>& node,
+bool initialize(MeshDistanceTraversalNode<BV, RelativeTransformationIsIdentity>& node,
                 BVHModel<BV>& model1, Transform3f& tf1,
                 BVHModel<BV>& model2, Transform3f& tf2,
                 const DistanceRequest& request,
@@ -627,27 +575,37 @@ bool initialize(MeshDistanceTraversalNode<BV>& node,
   return true;
 }
 
-
-/// @brief Initialize traversal node for distance computation between two meshes, specialized for RSS type
-bool initialize(MeshDistanceTraversalNodeRSS& node,
-                const BVHModel<RSS>& model1, const Transform3f& tf1,
-                const BVHModel<RSS>& model2, const Transform3f& tf2,
+/// @brief Initialize traversal node for distance computation between two meshes
+template<typename BV>
+bool initialize(MeshDistanceTraversalNode<BV, 0>& node,
+                const BVHModel<BV>& model1, const Transform3f& tf1,
+                const BVHModel<BV>& model2, const Transform3f& tf2,
                 const DistanceRequest& request,
-                DistanceResult& result);
+                DistanceResult& result)
+{
+  if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType() != BVH_MODEL_TRIANGLES)
+    return false;
 
-/// @brief Initialize traversal node for distance computation between two meshes, specialized for kIOS type
-bool initialize(MeshDistanceTraversalNodekIOS& node,
-                const BVHModel<kIOS>& model1, const Transform3f& tf1,
-                const BVHModel<kIOS>& model2, const Transform3f& tf2,
-                const DistanceRequest& request,
-                DistanceResult& result);
+  node.request = request;
+  node.result = &result;
 
-/// @brief Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type
-bool initialize(MeshDistanceTraversalNodeOBBRSS& node,
-                const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
-                const BVHModel<OBBRSS>& model2, const Transform3f& tf2,
-                const DistanceRequest& request,
-                DistanceResult& result);
+  node.model1 = &model1;
+  node.tf1 = tf1;
+  node.model2 = &model2;
+  node.tf2 = tf2;
+
+  node.vertices1 = model1.vertices;
+  node.vertices2 = model2.vertices;
+
+  node.tri_indices1 = model1.tri_indices;
+  node.tri_indices2 = model2.tri_indices;
+
+  relativeTransform(tf1.getRotation(), tf1.getTranslation(),
+      tf2.getRotation(), tf2.getTranslation(),
+      node.RT.R, node.RT.T);
+
+  return true;
+}
 
 /// @brief Initialize traversal node for distance computation between one mesh and one shape, given the current transforms
 template<typename BV, typename S>
diff --git a/include/hpp/fcl/mesh_loader/assimp.h b/include/hpp/fcl/mesh_loader/assimp.h
index 68748291dd9c9ce494040948dafc23d12e394bef..ded5ef893cc09aaa48dcd1af182be743816f90c5 100644
--- a/include/hpp/fcl/mesh_loader/assimp.h
+++ b/include/hpp/fcl/mesh_loader/assimp.h
@@ -75,7 +75,6 @@ struct Loader {
  *
  * @param[in]  scale           Scale to apply when reading the ressource
  * @param[in]  scene           Pointer to the assimp scene
- * @param[in]  node            Current node of the scene
  * @param[in]  vertices_offset Current number of vertices in the model
  * @param      tv              Triangles and Vertices of the mesh submodels
  */
diff --git a/include/hpp/fcl/shape/convex.h b/include/hpp/fcl/shape/convex.h
index cafbddd040b474fbab5204eb4c7d156869530db7..04b12daacb4f4c8dc729ee88d3eaed67a6898d55 100644
--- a/include/hpp/fcl/shape/convex.h
+++ b/include/hpp/fcl/shape/convex.h
@@ -46,15 +46,15 @@ namespace hpp
 namespace fcl
 {
 
-/// @brief Convex polytope 
+/// @brief Convex polytope
 /// @tparam PolygonT the polygon class. It must have method \c size() and
 ///         \c operator[](int i)
 template <typename PolygonT>
 class Convex : public ConvexBase
 {
 public:
-  /// @brief Constructing a convex, providing normal and offset of each polytype surface, and the points and shape topology information 
-  /// \param own_storage whether this class owns the pointers of points and
+  /// @brief Constructing a convex, providing normal and offset of each polytype surface, and the points and shape topology information
+  /// \param ownStorage whether this class owns the pointers of points and
   ///                    polygons. If owned, they are deleted upon destruction.
   /// \param points_ list of 3D points
   /// \param num_points_ number of 3D points
diff --git a/include/hpp/fcl/shape/geometric_shapes.h b/include/hpp/fcl/shape/geometric_shapes.h
index e0a9dfb343227f9d7c34f368b6485cc327d767d1..d2f2d77a06b3e96de5fd649964d1cd99f05dc245 100644
--- a/include/hpp/fcl/shape/geometric_shapes.h
+++ b/include/hpp/fcl/shape/geometric_shapes.h
@@ -62,8 +62,8 @@ public:
   OBJECT_TYPE getObjectType() const { return OT_GEOM; }
 };
 
-/// @defgroup Geometric_Shapes
-/// regroup class of differents types of geometric shapes.
+/// @defgroup Geometric_Shapes Geometric shapes
+/// Classes of different types of geometric shapes.
 /// @{
 
 /// @brief Triangle stores the points instead of only indices of points
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 9e4e1dc2a76000042985368d4cfa91d83842fd4c..1ed2ace31dea793f9d60954e18d6726a22fe4ea7 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -66,10 +66,7 @@ set(${LIBRARY_NAME}_SOURCES
   distance_sphere_plane.cpp
   intersect.cpp
   math/transform.cpp
-  traversal/traversal_node_setup.cpp
-  traversal/traversal_node_bvhs.cpp
   traversal/traversal_recurse.cpp
-  traversal/traversal_node_base.cpp
   profile.cpp
   distance.cpp
   BVH/BVH_utility.cpp
diff --git a/src/collision.cpp b/src/collision.cpp
index b07f2b5d69292b1f64488533b23a1ef8aa8de857..c111360f01fbf9c7cf13b396633392a0f1fce22e 100644
--- a/src/collision.cpp
+++ b/src/collision.cpp
@@ -70,19 +70,27 @@ void invertResults(CollisionResult& result)
     }
 }
 
+std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
+                    const CollisionRequest& request, CollisionResult& result)
+{
+  return collide(
+      o1->collisionGeometry().get(), o1->getTransform(),
+      o2->collisionGeometry().get(), o2->getTransform(),
+      request, result);
+}
+
 std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
                     const CollisionGeometry* o2, const Transform3f& tf2,
-                    const GJKSolver* nsolver_,
-                    const CollisionRequest& request,
-                    CollisionResult& result)
+                    const CollisionRequest& request, CollisionResult& result)
 {
-  const GJKSolver* nsolver = nsolver_;
-  if(!nsolver_)
-    nsolver = new GJKSolver();  
+  GJKSolver solver;
+  solver.enable_cached_guess = request.enable_cached_gjk_guess;
+  if (solver.enable_cached_guess)
+    solver.cached_guess = request.cached_gjk_guess;
 
   const CollisionFunctionMatrix& looktable = getCollisionFunctionLookTable();
   result.distance_lower_bound = -1;
-  std::size_t res; 
+  std::size_t res;
   if(request.num_max_contacts == 0)
   {
     std::cerr << "Warning: should stop early as num_max_contact is " << request.num_max_contacts << " !" << std::endl;
@@ -94,9 +102,9 @@ std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
     OBJECT_TYPE object_type2 = o2->getObjectType();
     NODE_TYPE node_type1 = o1->getNodeType();
     NODE_TYPE node_type2 = o2->getNodeType();
-  
+
     if(object_type1 == OT_GEOM && object_type2 == OT_BVH)
-    {  
+    {
       if(!looktable.collision_matrix[node_type2][node_type1])
       {
         std::cerr << "Warning: collision function between node type " << node_type1 << " and node type " << node_type2 << " is not supported"<< std::endl;
@@ -104,7 +112,7 @@ std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
       }
       else
       {
-        res = looktable.collision_matrix[node_type2][node_type1](o2, tf2, o1, tf1, nsolver, request, result);
+        res = looktable.collision_matrix[node_type2][node_type1](o2, tf2, o1, tf1, &solver, request, result);
         invertResults(result);
       }
     }
@@ -116,56 +124,15 @@ std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
         res = 0;
       }
       else
-        res = looktable.collision_matrix[node_type1][node_type2](o1, tf1, o2, tf2, nsolver, request, result);
+        res = looktable.collision_matrix[node_type1][node_type2](o1, tf1, o2, tf2, &solver, request, result);
     }
   }
+  if (solver.enable_cached_guess)
+    result.cached_gjk_guess = solver.cached_guess;
 
-  if(!nsolver_)
-    delete nsolver;
-  
   return res;
 }
 
-std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
-                    const GJKSolver* nsolver,
-                    const CollisionRequest& request,
-                    CollisionResult& result)
-{
-  return collide(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver, request, result);
-}
-
-std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
-                    const CollisionRequest& request, CollisionResult& result)
-{
-  switch(request.gjk_solver_type)
-  {
-  case GST_INDEP:
-    {
-      GJKSolver solver;
-      return collide(o1, o2, &solver, request, result);
-    }
-  default:
-    return -1; // error
-  }
-}
-
-std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
-                    const CollisionGeometry* o2, const Transform3f& tf2,
-                    const CollisionRequest& request, CollisionResult& result)
-{
-  switch(request.gjk_solver_type)
-  {
-  case GST_INDEP:
-    {
-      GJKSolver solver;
-      return collide(o1, tf1, o2, tf2, &solver, request, result);
-    }
-  default:
-    std::cerr << "Warning! Invalid GJK solver" << std::endl;
-    return -1; // error
-  }
-}
-
 }
 
 
diff --git a/src/collision_data.cpp b/src/collision_data.cpp
index b71b0e479df36870cc9c94576d5b29f31d1a6398..d2eae6ba9555240e7925a7baabea710d7feeb9ff 100644
--- a/src/collision_data.cpp
+++ b/src/collision_data.cpp
@@ -55,12 +55,10 @@ bool DistanceRequest::isSatisfied(const DistanceResult& result) const
   CollisionRequest::CollisionRequest
   (size_t num_max_contacts_, bool enable_contact_,
    bool enable_distance_lower_bound_, size_t /*num_max_cost_sources_*/,
-   bool /*enable_cost_*/, bool /*use_approximate_cost_*/,
-   GJKSolverType gjk_solver_type_) :
+   bool /*enable_cost_*/, bool /*use_approximate_cost_*/) :
     num_max_contacts(num_max_contacts_),
     enable_contact(enable_contact_),
     enable_distance_lower_bound (enable_distance_lower_bound_),
-    gjk_solver_type(gjk_solver_type_),
     security_margin (0),
     break_distance (1e-3)
   {
diff --git a/src/collision_func_matrix.cpp b/src/collision_func_matrix.cpp
index efffb50c2394f05a55136bb80247c8fc9da075aa..dab1eb9c46e5fbc704a41e5cd0fc62d085a66436 100644
--- a/src/collision_func_matrix.cpp
+++ b/src/collision_func_matrix.cpp
@@ -84,24 +84,27 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3f& tf
 
   if (distance <= 0) {
     if (result.numContacts () < request.num_max_contacts) {
-      Contact contact (o1, o2, distanceResult.b1, distanceResult.b2);
       const Vec3f& p1 = distanceResult.nearest_points [0];
-      assert (p1 == distanceResult.nearest_points [1]);
-      contact.pos = p1;
-      contact.normal = distanceResult.normal;
-      contact.penetration_depth = -distance;
+      assert (!request.enable_contact || p1 == distanceResult.nearest_points [1]);
+
+      Contact contact (o1, o2, distanceResult.b1, distanceResult.b2,
+          p1,
+          distanceResult.normal,
+          -distance+request.security_margin);
+
       result.addContact (contact);
     }
     return 1;
   }
   if (distance <= request.security_margin) {
     if (result.numContacts () < request.num_max_contacts) {
-      Contact contact (o1, o2, distanceResult.b1, distanceResult.b2);
       const Vec3f& p1 = distanceResult.nearest_points [0];
       const Vec3f& p2 = distanceResult.nearest_points [1];
-      contact.pos = .5 * (p1 + p2);
-      contact.normal = (p2-p1).normalized ();
-      contact.penetration_depth = -distance;
+
+      Contact contact (o1, o2, distanceResult.b1, distanceResult.b2,
+          .5 * (p1 + p2),
+          (p2-p1).normalized (),
+          -distance+request.security_margin);
       result.addContact (contact);
     }
     return 1;
@@ -112,27 +115,26 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3f& tf
 
 namespace details
 {
-
-template<typename OrientMeshShapeCollisionTraveralNode, typename T_BVH, typename T_SH>
-std::size_t orientedBVHShapeCollide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
-                                    const GJKSolver* nsolver,
-                                    const CollisionRequest& request, CollisionResult& result)
-{
-  if(request.isSatisfied(result)) return result.numContacts();
-
-  OrientMeshShapeCollisionTraveralNode node (request);
-  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>* >(o1);
-  const T_SH* obj2 = static_cast<const T_SH*>(o2);
-
-  initialize(node, *obj1, tf1, *obj2, tf2, nsolver, result);
-  fcl::collide(&node, request, result);
-  return result.numContacts();
-}
-
+  template<typename T_BVH, typename T_SH> struct bvh_shape_traits
+  {
+    enum { Options = RelativeTransformationIsIdentity };
+  };
+#define BVH_SHAPE_DEFAULT_TO_ORIENTED(bv)                                      \
+  template<typename T_SH> struct bvh_shape_traits<bv, T_SH>                    \
+  { enum { Options = 0 }; }
+  BVH_SHAPE_DEFAULT_TO_ORIENTED(OBB);
+  BVH_SHAPE_DEFAULT_TO_ORIENTED(RSS);
+  BVH_SHAPE_DEFAULT_TO_ORIENTED(kIOS);
+  BVH_SHAPE_DEFAULT_TO_ORIENTED(OBBRSS);
+#undef BVH_SHAPE_DEFAULT_TO_ORIENTED
 }
 
-
-template<typename T_BVH, typename T_SH>
+/// \tparam _Options takes two values.
+///         - RelativeTransformationIsIdentity if object 1 should be moved the
+///           into the frame of object 2 before computing collisions.
+///         - 0 if the query should be made with non-aligned object frames.
+template<typename T_BVH, typename T_SH,
+  int _Options = details::bvh_shape_traits<T_BVH, T_SH>::Options>
 struct BVHShapeCollider
 {
   static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
@@ -141,7 +143,19 @@ struct BVHShapeCollider
   {
     if(request.isSatisfied(result)) return result.numContacts();
 
-    MeshShapeCollisionTraversalNode<T_BVH, T_SH> node (request);
+    if (_Options & RelativeTransformationIsIdentity)
+      return aligned(o1, tf1, o2, tf2, nsolver, request, result);
+    else
+      return oriented(o1, tf1, o2, tf2, nsolver, request, result);
+  }
+
+  static std::size_t aligned(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
+                             const GJKSolver* nsolver,
+                             const CollisionRequest& request, CollisionResult& result)
+  {
+    if(request.isSatisfied(result)) return result.numContacts();
+
+    MeshShapeCollisionTraversalNode<T_BVH, T_SH, RelativeTransformationIsIdentity> node (request);
     const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>* >(o1);
     BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
     Transform3f tf1_tmp = tf1;
@@ -153,53 +167,22 @@ struct BVHShapeCollider
     delete obj1_tmp;
     return result.numContacts();
   }
-};
-
-template<typename T_SH>
-struct BVHShapeCollider<OBB, T_SH>
-{
-  static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
-                             const GJKSolver* nsolver,
-                             const CollisionRequest& request, CollisionResult& result)
-  {
-    return details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBB<T_SH>, OBB, T_SH>(o1, tf1, o2, tf2, nsolver, request, result);
-  } 
-};
-
 
-template<typename T_SH>
-struct BVHShapeCollider<RSS, T_SH>
-{
-  static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
-                             const GJKSolver* nsolver,
-                             const CollisionRequest& request, CollisionResult& result)
+  static std::size_t oriented(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
+      const GJKSolver* nsolver,
+      const CollisionRequest& request, CollisionResult& result)
   {
-    return details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeRSS<T_SH>, RSS, T_SH>(o1, tf1, o2, tf2, nsolver, request, result);
-  } 
-};
-
+    if(request.isSatisfied(result)) return result.numContacts();
 
-template<typename T_SH>
-struct BVHShapeCollider<kIOS, T_SH>
-{
-  static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
-                             const GJKSolver* nsolver,
-                             const CollisionRequest& request, CollisionResult& result)
-  {
-    return details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodekIOS<T_SH>, kIOS, T_SH>(o1, tf1, o2, tf2, nsolver, request, result);
-  } 
-};
+    MeshShapeCollisionTraversalNode<T_BVH, T_SH, 0> node (request);
+    const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>* >(o1);
+    const T_SH* obj2 = static_cast<const T_SH*>(o2);
 
+    initialize(node, *obj1, tf1, *obj2, tf2, nsolver, result);
+    fcl::collide(&node, request, result);
+    return result.numContacts();
+  }
 
-template<typename T_SH>
-struct BVHShapeCollider<OBBRSS, T_SH>
-{
-  static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, 
-                             const GJKSolver* nsolver,
-                             const CollisionRequest& request, CollisionResult& result)
-  {
-    return details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS<T_SH>, OBBRSS, T_SH>(o1, tf1, o2, tf2, nsolver, request, result);
-  } 
 };
 
 namespace details
diff --git a/src/distance.cpp b/src/distance.cpp
index 95c4a8b2ee9cd2ae4d1ef757939dbe83b5d19322..83b734cf13106204c82430c0a6af4d64d5514260 100644
--- a/src/distance.cpp
+++ b/src/distance.cpp
@@ -52,14 +52,19 @@ DistanceFunctionMatrix& getDistanceFunctionLookTable()
   return table;
 }
 
-FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, 
+FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const DistanceRequest& request, DistanceResult& result)
+{
+  return distance(
+      o1->collisionGeometry().get(), o1->getTransform(),
+      o2->collisionGeometry().get(), o2->getTransform(),
+      request, result);
+}
+
+FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
                   const CollisionGeometry* o2, const Transform3f& tf2,
-                  const GJKSolver* nsolver_,
                   const DistanceRequest& request, DistanceResult& result)
 {
-  const GJKSolver* nsolver = nsolver_;
-  if(!nsolver_) 
-    nsolver = new GJKSolver();
+  GJKSolver solver;
 
   const DistanceFunctionMatrix& looktable = getDistanceFunctionLookTable();
 
@@ -78,7 +83,7 @@ FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
     }
     else
     {
-      res = looktable.distance_matrix[node_type2][node_type1](o2, tf2, o1, tf1, nsolver, request, result);
+      res = looktable.distance_matrix[node_type2][node_type1](o2, tf2, o1, tf1, &solver, request, result);
       // If closest points are requested, switch object 1 and 2
       if (request.enable_nearest_points) {
 	const CollisionGeometry *tmpo = result.o1;
@@ -98,53 +103,13 @@ FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
     }
     else
     {
-      res = looktable.distance_matrix[node_type1][node_type2](o1, tf1, o2, tf2, nsolver, request, result);    
+      res = looktable.distance_matrix[node_type1][node_type2](o1, tf1, o2, tf2, &solver, request, result);    
     }
   }
 
-  if(!nsolver_)
-    delete nsolver;
-
   return res;
 }
 
-FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const GJKSolver* nsolver,
-                  const DistanceRequest& request, DistanceResult& result)
-{
-  return distance(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver,
-                                     request, result);
-}
-
-FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const DistanceRequest& request, DistanceResult& result)
-{
-  switch(request.gjk_solver_type)
-  {
-  case GST_INDEP:
-    {
-      GJKSolver solver;
-      return distance(o1, o2, &solver, request, result);
-    }
-  default:
-    return -1; // error
-  }
-}
-
-FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
-                  const CollisionGeometry* o2, const Transform3f& tf2,
-                  const DistanceRequest& request, DistanceResult& result)
-{
-  switch(request.gjk_solver_type)
-  {
-  case GST_INDEP:
-    {
-      GJKSolver solver;
-      return distance(o1, tf1, o2, tf2, &solver, request, result);
-    }
-  default:
-    return -1;
-  }
-}
-
 
 }
 
diff --git a/src/distance_capsule_capsule.cpp b/src/distance_capsule_capsule.cpp
index aa870d7ca640166229e54770aa06d6751d8d1d80..22a6b1f17a067101d20487c8909b1884afe3ac14 100644
--- a/src/distance_capsule_capsule.cpp
+++ b/src/distance_capsule_capsule.cpp
@@ -158,36 +158,6 @@ namespace fcl {
     return distance;
   }
 
-  template <>
-  std::size_t ShapeShapeCollide <Capsule, Capsule>
-  (const CollisionGeometry* o1, const Transform3f& tf1,
-   const CollisionGeometry* o2, const Transform3f& tf2,
-   const GJKSolver*, const CollisionRequest& request,
-   CollisionResult& result)
-  {
-    GJKSolver* unused = 0x0;
-    DistanceResult distanceResult;
-    DistanceRequest distanceRequest (request.enable_contact);
-
-    FCL_REAL distance = ShapeShapeDistance <Capsule, Capsule>
-      (o1, tf1, o2, tf2, unused, distanceRequest, distanceResult);
-
-    if (distance > 0)
-    {
-      return 0;
-    }
-    else
-    {
-      Contact contact (o1, o2, -1, -1);
-      const Vec3f& p1 = distanceResult.nearest_points [0];
-      const Vec3f& p2 = distanceResult.nearest_points [1];
-      contact.pos = 0.5 * (p1+p2);
-      contact.normal = distanceResult.normal;
-      result.addContact(contact);
-      return 1;
-    }
-  }
-
 } // namespace fcl
 
 } // namespace hpp
diff --git a/src/traversal/traversal_node_base.cpp b/src/traversal/traversal_node_base.cpp
deleted file mode 100644
index 7ae6ab13286f29f06c8035d2f117a933255d9f7e..0000000000000000000000000000000000000000
--- a/src/traversal/traversal_node_base.cpp
+++ /dev/null
@@ -1,112 +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 */
-
-
-#include <hpp/fcl/internal/traversal_node_base.h>
-#include <limits>
-
-namespace hpp
-{
-namespace fcl
-{
-
-TraversalNodeBase::~TraversalNodeBase()
-{
-}
-
-  bool TraversalNodeBase::isFirstNodeLeaf(int /*b*/) const
-{
-  return true;
-}
-
-  bool TraversalNodeBase::isSecondNodeLeaf(int /*b*/) const
-{
-  return true;
-}
-
-  bool TraversalNodeBase::firstOverSecond(int /*b1*/, int /*b2*/) const
-{
-  return true;
-}
-
-int TraversalNodeBase::getFirstLeftChild(int b) const
-{
-  return b;
-}
-
-int TraversalNodeBase::getFirstRightChild(int b) const
-{
-  return b;
-}
-
-int TraversalNodeBase::getSecondLeftChild(int b) const
-{
-  return b;
-}
-
-int TraversalNodeBase::getSecondRightChild(int b) const
-{
-  return b;
-}
-
-CollisionTraversalNodeBase::~CollisionTraversalNodeBase()
-{
-}
-
-bool CollisionTraversalNodeBase::canStop() const
-{
-  return false;
-}
-
-
-DistanceTraversalNodeBase::~DistanceTraversalNodeBase()
-{
-}
-
-  FCL_REAL DistanceTraversalNodeBase::BVDistanceLowerBound(int /*b1*/, int /*b2*/) const
-{
-  return std::numeric_limits<FCL_REAL>::max();
-}
-
-  bool DistanceTraversalNodeBase::canStop(FCL_REAL /*c*/) const
-{
-  return false;
-}
-
-}
-
-} // namespace hpp
diff --git a/src/traversal/traversal_node_bvhs.cpp b/src/traversal/traversal_node_bvhs.cpp
deleted file mode 100644
index cdaeddbecf728bc79ff218f7b12114786eb23f4d..0000000000000000000000000000000000000000
--- a/src/traversal/traversal_node_bvhs.cpp
+++ /dev/null
@@ -1,226 +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 */
-
-
-#include <hpp/fcl/internal/traversal_node_bvhs.h>
-
-namespace hpp
-{
-namespace fcl
-{
-
-namespace details
-{
-template<typename BV>
-static inline void meshDistanceOrientedNodeleafComputeDistance(int b1, int b2,
-                                                       const BVHModel<BV>* model1, const BVHModel<BV>* model2,
-                                                       Vec3f* vertices1, Vec3f* vertices2, 
-                                                       Triangle* tri_indices1, Triangle* tri_indices2,
-                                                       const Matrix3f& R, const Vec3f& T,
-                                                       bool enable_statistics,
-                                                       int& num_leaf_tests,
-                                                       const DistanceRequest&,
-                                                       DistanceResult& result)
-{
-  if(enable_statistics) num_leaf_tests++;
-
-  const BVNode<BV>& node1 = model1->getBV(b1);
-  const BVNode<BV>& node2 = model2->getBV(b2);
-
-  int primitive_id1 = node1.primitiveId();
-  int primitive_id2 = node2.primitiveId();
-
-  const Triangle& tri_id1 = tri_indices1[primitive_id1];
-  const Triangle& tri_id2 = tri_indices2[primitive_id2];
-
-  const Vec3f& t11 = vertices1[tri_id1[0]];
-  const Vec3f& t12 = vertices1[tri_id1[1]];
-  const Vec3f& t13 = vertices1[tri_id1[2]];
-
-  const Vec3f& t21 = vertices2[tri_id2[0]];
-  const Vec3f& t22 = vertices2[tri_id2[1]];
-  const Vec3f& t23 = vertices2[tri_id2[2]];
-
-  // nearest point pair
-  Vec3f P1, P2, normal;
-
-  FCL_REAL d = sqrt (TriangleDistance::sqrTriDistance
-		     (t11, t12, t13, t21, t22, t23, R, T, P1, P2));
-
-  result.update(d, model1, model2, primitive_id1, primitive_id2, P1, P2,
-                normal);
-}
-} // namespace details
-
-namespace details
-{
-
-template<typename BV>
-static inline void distancePreprocessOrientedNode(const BVHModel<BV>* model1, const BVHModel<BV>* model2,
-                                                  const Vec3f* vertices1, Vec3f* vertices2,
-                                                  Triangle* tri_indices1, Triangle* tri_indices2,
-                                                  int init_tri_id1, int init_tri_id2,
-                                                  const Matrix3f& R, const Vec3f& T,
-                                                  const DistanceRequest&,
-                                                  DistanceResult& result)
-{
-  const Triangle& init_tri1 = tri_indices1[init_tri_id1];
-  const Triangle& init_tri2 = tri_indices2[init_tri_id2];
-
-  Vec3f init_tri1_points[3];
-  Vec3f init_tri2_points[3];
-
-  init_tri1_points[0] = vertices1[init_tri1[0]];
-  init_tri1_points[1] = vertices1[init_tri1[1]];
-  init_tri1_points[2] = vertices1[init_tri1[2]];
-
-  init_tri2_points[0] = vertices2[init_tri2[0]];
-  init_tri2_points[1] = vertices2[init_tri2[1]];
-  init_tri2_points[2] = vertices2[init_tri2[2]];
-
-  Vec3f p1, p2, normal;
-  FCL_REAL distance = sqrt (TriangleDistance::sqrTriDistance
-			    (init_tri1_points[0], init_tri1_points[1],
-			     init_tri1_points[2], init_tri2_points[0],
-			     init_tri2_points[1], init_tri2_points[2],
-			     R, T, p1, p2));
-
-  result.update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2,
-                normal);
-}
-
-template<typename BV>
-static inline void distancePostprocessOrientedNode(const BVHModel<BV>* model1, const BVHModel<BV>* model2,
-                                                   const Transform3f& tf1, const DistanceRequest& request, DistanceResult& result)
-{
-  /// the points obtained by triDistance are not in world space: both are in object1's local coordinate system, so we need to convert them into the world space.
-  if(request.enable_nearest_points && (result.o1 == model1) && (result.o2 == model2))
-  {
-    result.nearest_points[0] = tf1.transform(result.nearest_points[0]).eval();
-    result.nearest_points[1] = tf1.transform(result.nearest_points[1]).eval();
-  }
-}
-
-}
-
-MeshDistanceTraversalNodeRSS::MeshDistanceTraversalNodeRSS() : MeshDistanceTraversalNode<RSS>()
-{
-  R.setIdentity();
-}
-
-void MeshDistanceTraversalNodeRSS::preprocess()
-{
-  details::distancePreprocessOrientedNode(model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 0, 0, R, T, request, *result);
-}
-
-void MeshDistanceTraversalNodeRSS::postprocess()
-{
-  details::distancePostprocessOrientedNode(model1, model2, tf1, request, *result);
-}
-
-FCL_REAL MeshDistanceTraversalNodeRSS::BVDistanceLowerBound(int b1, int b2) const
-{
-  if(enable_statistics) num_bv_tests++;
-  return distance(R, T, model1->getBV(b1).bv, model2->getBV(b2).bv);
-}
-
-void MeshDistanceTraversalNodeRSS::leafComputeDistance(int b1, int b2) const
-{
-  details::meshDistanceOrientedNodeleafComputeDistance(b1, b2, model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 
-                                               R, T, enable_statistics, num_leaf_tests, 
-                                               request, *result);
-}
-
-MeshDistanceTraversalNodekIOS::MeshDistanceTraversalNodekIOS() : MeshDistanceTraversalNode<kIOS>()
-{
-  R.setIdentity();
-}
-
-void MeshDistanceTraversalNodekIOS::preprocess()
-{
-  details::distancePreprocessOrientedNode(model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 0, 0, R, T, request, *result);
-}
-
-void MeshDistanceTraversalNodekIOS::postprocess()
-{
-  details::distancePostprocessOrientedNode(model1, model2, tf1, request, *result);
-}
-
-FCL_REAL MeshDistanceTraversalNodekIOS::BVDistanceLowerBound(int b1, int b2) const
-{
-  if(enable_statistics) num_bv_tests++;
-  return distance(R, T, model1->getBV(b1).bv, model2->getBV(b2).bv);
-}
-
-void MeshDistanceTraversalNodekIOS::leafComputeDistance(int b1, int b2) const
-{
-  details::meshDistanceOrientedNodeleafComputeDistance(b1, b2, model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 
-                                               R, T, enable_statistics, num_leaf_tests, 
-                                               request, *result);
-}
-
-MeshDistanceTraversalNodeOBBRSS::MeshDistanceTraversalNodeOBBRSS() : MeshDistanceTraversalNode<OBBRSS>()
-{
-  R.setIdentity();
-}
-
-void MeshDistanceTraversalNodeOBBRSS::preprocess()
-{
-  details::distancePreprocessOrientedNode(model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 0, 0, R, T, request, *result);
-}
-
-void MeshDistanceTraversalNodeOBBRSS::postprocess()
-{
-  details::distancePostprocessOrientedNode(model1, model2, tf1, request, *result);
-}
-
-FCL_REAL MeshDistanceTraversalNodeOBBRSS::BVDistanceLowerBound(int b1, int b2) const
-{
-  if(enable_statistics) num_bv_tests++;
-  return distance(R, T, model1->getBV(b1).bv, model2->getBV(b2).bv);
-}
-
-void MeshDistanceTraversalNodeOBBRSS::leafComputeDistance(int b1, int b2) const
-{
-  details::meshDistanceOrientedNodeleafComputeDistance(b1, b2, model1, model2, vertices1, vertices2, tri_indices1, tri_indices2, 
-                                               R, T, enable_statistics, num_leaf_tests, 
-                                               request, *result);
-}
-
-}
-
-} // namespace hpp
diff --git a/src/traversal/traversal_node_setup.cpp b/src/traversal/traversal_node_setup.cpp
deleted file mode 100644
index b0d13e489e719ee648d1e17f6a62236bcbbee824..0000000000000000000000000000000000000000
--- a/src/traversal/traversal_node_setup.cpp
+++ /dev/null
@@ -1,117 +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 */
-
-
-#include <hpp/fcl/internal/traversal_node_setup.h>
-#include <hpp/fcl/internal/tools.h>
-namespace hpp
-{
-namespace fcl
-{
-
-namespace details
-{
-template<typename BV, typename OrientedNode>
-static inline bool setupMeshDistanceOrientedNode(OrientedNode& node,
-                                                 const BVHModel<BV>& model1, const Transform3f& tf1,
-                                                 const BVHModel<BV>& model2, const Transform3f& tf2,
-                                                 const DistanceRequest& request,
-                                                 DistanceResult& result)
-{
-  if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType() != BVH_MODEL_TRIANGLES)
-    return false;
-
-  node.request = request;
-  node.result = &result;
-
-  node.model1 = &model1;
-  node.tf1 = tf1;
-  node.model2 = &model2;
-  node.tf2 = tf2;
-
-  node.vertices1 = model1.vertices;
-  node.vertices2 = model2.vertices;
-
-  node.tri_indices1 = model1.tri_indices;
-  node.tri_indices2 = model2.tri_indices;
-
-  relativeTransform(tf1.getRotation(), tf1.getTranslation(), tf2.getRotation(), tf2.getTranslation(), node.R, node.T);
-
-  return true;
-}
-
-
-}
-
-bool initialize(MeshDistanceTraversalNodeRSS& node,
-                const BVHModel<RSS>& model1, const Transform3f& tf1,
-                const BVHModel<RSS>& model2, const Transform3f& tf2,
-                const DistanceRequest& request,
-                DistanceResult& result)
-{
-  return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
-}
-
-
-bool initialize(MeshDistanceTraversalNodekIOS& node,
-                const BVHModel<kIOS>& model1, const Transform3f& tf1,
-                const BVHModel<kIOS>& model2, const Transform3f& tf2,
-                const DistanceRequest& request,
-                DistanceResult& result)
-{
-  return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
-}
-
-bool initialize(MeshDistanceTraversalNodeOBBRSS& node,
-                const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
-                const BVHModel<OBBRSS>& model2, const Transform3f& tf2,
-                const DistanceRequest& request,
-                DistanceResult& result)
-{
-  return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
-}
-
-namespace details
-{
-
-
-}
-
-
-}
-
-} // namespace hpp
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 86201e6d73fbe99130fd22c7f13e65dd4075306b..a98c362eda13f938dc114e4b2cb68dff48173df8 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -1,22 +1,21 @@
 config_files(fcl_resources/config.h)
 
-macro(add_fcl_test test_name)
-  add_executable(${ARGV})
+macro(add_fcl_test test_name source)
+  ADD_UNIT_TEST(${test_name} ${source})
   target_link_libraries(${test_name}
     PUBLIC
-    ${PROJECT_NAME}
+    hpp-fcl
     ${Boost_LIBRARIES}
     Boost::unit_test_framework
     utility
     )
   PKG_CONFIG_USE_DEPENDENCY(${test_name} assimp)
-  add_test(${test_name} ${EXECUTABLE_OUTPUT_PATH}/${test_name})
   target_compile_options(${test_name} PRIVATE "-Wno-c99-extensions")
 endmacro(add_fcl_test)
 
 include_directories(${CMAKE_CURRENT_BINARY_DIR})
 
-IF(RUN_TESTS)
+IF(BUILD_TESTING)
   add_library(utility STATIC utility.cpp)
 ELSE()
   add_library(utility STATIC EXCLUDE_FROM_ALL utility.cpp)
@@ -54,7 +53,11 @@ if(HPP_FCL_HAVE_OCTOMAP)
 endif(HPP_FCL_HAVE_OCTOMAP)
 
 ## Benchmark
-add_executable(test-benchmark benchmark.cpp)
+IF(BUILD_TESTING)
+  add_executable(test-benchmark benchmark.cpp)
+ELSE()
+  add_executable(test-benchmark EXCLUDE_FROM_ALL benchmark.cpp)
+ENDIF()
 target_link_libraries(test-benchmark 
   PUBLIC 
   utility
diff --git a/test/box_box_distance.cpp b/test/box_box_distance.cpp
index 90d090e30f2c0853ef2bc0449536cf039a3d87ba..9cc3ccaecd4d87d9c7ebd413cb7c3689a68b0b86 100644
--- a/test/box_box_distance.cpp
+++ b/test/box_box_distance.cpp
@@ -58,7 +58,6 @@ using hpp::fcl::Vec3f;
 using hpp::fcl::CollisionObject;
 using hpp::fcl::DistanceResult;
 using hpp::fcl::DistanceRequest;
-using hpp::fcl::GST_INDEP;
 
 BOOST_AUTO_TEST_CASE(distance_box_box_1)
 {
@@ -72,7 +71,7 @@ BOOST_AUTO_TEST_CASE(distance_box_box_1)
   CollisionObject o2 (s2, tf2);
 
   // Enable computation of nearest points
-  DistanceRequest distanceRequest (true, 0, 0, GST_INDEP);
+  DistanceRequest distanceRequest (true, 0, 0);
   DistanceResult distanceResult;
 
   hpp::fcl::distance (&o1, &o2, distanceRequest, distanceResult);
@@ -116,7 +115,7 @@ BOOST_AUTO_TEST_CASE(distance_box_box_2)
   CollisionObject o2 (s2, tf2);
 
   // Enable computation of nearest points
-  DistanceRequest distanceRequest (true, 0, 0, GST_INDEP);
+  DistanceRequest distanceRequest (true, 0, 0);
   DistanceResult distanceResult;
 
   hpp::fcl::distance (&o1, &o2, distanceRequest, distanceResult);
@@ -157,7 +156,7 @@ BOOST_AUTO_TEST_CASE(distance_box_box_3)
   CollisionObject o2 (s2, tf2);
 
   // Enable computation of nearest points
-  DistanceRequest distanceRequest (true, 0, 0, GST_INDEP);
+  DistanceRequest distanceRequest (true, 0, 0);
   DistanceResult distanceResult;
 
   hpp::fcl::distance (&o1, &o2, distanceRequest, distanceResult);
diff --git a/test/bvh_models.cpp b/test/bvh_models.cpp
index 4e8990cac95b2391b5f6d85b30d9aa1792d7140a..ff2bf14037856a914df218c16362458e4e458b42 100644
--- a/test/bvh_models.cpp
+++ b/test/bvh_models.cpp
@@ -71,7 +71,7 @@ void testBVHModelPointCloud()
     return;
   }
 
-  Box box;
+  Box box (Vec3f::Ones());
   double a = box.halfSide[0];
   double b = box.halfSide[1];
   double c = box.halfSide[2];
@@ -110,7 +110,7 @@ template<typename BV>
 void testBVHModelTriangles()
 {
   boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
-  Box box(1,1,1);
+  Box box (Vec3f::Ones());
   AABB aabb (Vec3f(-1,0,-1), Vec3f(1,1,1));
 
   double a = box.halfSide[0];
@@ -200,7 +200,7 @@ template<typename BV>
 void testBVHModelSubModel()
 {
   boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
-  Box box;
+  Box box (Vec3f::Ones());
 
   double a = box.halfSide[0];
   double b = box.halfSide[1];
diff --git a/test/capsule_box_1.cpp b/test/capsule_box_1.cpp
index 9f034b4f62f39edbf70a521e7b3ad77131f272f1..3de8f633d56b4ba308ae41efdf33c17af505e13f 100644
--- a/test/capsule_box_1.cpp
+++ b/test/capsule_box_1.cpp
@@ -60,7 +60,7 @@ BOOST_AUTO_TEST_CASE(distance_capsule_box)
   CollisionGeometryPtr_t boxGeometry (new hpp::fcl::Box (1., 2., 4.));
 
   // Enable computation of nearest points
-  hpp::fcl::DistanceRequest distanceRequest (true, 0, 0, hpp::fcl::GST_INDEP);
+  hpp::fcl::DistanceRequest distanceRequest (true, 0, 0);
   hpp::fcl::DistanceResult distanceResult;
   
   hpp::fcl::Transform3f tf1 (hpp::fcl::Vec3f (3., 0, 0));
diff --git a/test/capsule_box_2.cpp b/test/capsule_box_2.cpp
index 8a20117ab404ec0d648811b71ef71231968e1ad7..2f3114b1ea8c15206b0593eb15ee5a3d48beb7bc 100644
--- a/test/capsule_box_2.cpp
+++ b/test/capsule_box_2.cpp
@@ -60,7 +60,7 @@ BOOST_AUTO_TEST_CASE(distance_capsule_box)
   CollisionGeometryPtr_t boxGeometry (new hpp::fcl::Box (1., 2., 4.));
 
   // Enable computation of nearest points
-  hpp::fcl::DistanceRequest distanceRequest (true, 0, 0, hpp::fcl::GST_INDEP);
+  hpp::fcl::DistanceRequest distanceRequest (true, 0, 0);
   hpp::fcl::DistanceResult distanceResult;
 
   // Rotate capsule around y axis by pi/2 and move it behind box
diff --git a/test/capsule_capsule.cpp b/test/capsule_capsule.cpp
index ef1effd3fedf30037d3caeb284956193b888db53..ce492d2a154c82d175dca37204e5d6e919278be2 100644
--- a/test/capsule_capsule.cpp
+++ b/test/capsule_capsule.cpp
@@ -99,7 +99,11 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_trivial)
     size_t sphere_num_collisions = collide(&sphere_o1, &sphere_o2, collisionRequest, sphere_collisionResult);
     size_t capsule_num_collisions = collide(&capsule_o1, &capsule_o2, collisionRequest, capsule_collisionResult);
     
-    BOOST_CHECK(sphere_num_collisions == capsule_num_collisions);
+    BOOST_CHECK_EQUAL(sphere_num_collisions, capsule_num_collisions);
+    if (sphere_num_collisions == 0 && capsule_num_collisions == 0)
+      BOOST_CHECK_CLOSE(sphere_collisionResult.distance_lower_bound,
+                        capsule_collisionResult.distance_lower_bound,
+                        1e-6);
   }
 }
 
diff --git a/test/geometric_shapes.cpp b/test/geometric_shapes.cpp
index ea57e378e1e17b1f9efcf9164834e3d232d3c95c..85fc93723706738a637c3ad6cd8aee139c8794fc 100644
--- a/test/geometric_shapes.cpp
+++ b/test/geometric_shapes.cpp
@@ -63,7 +63,6 @@ template <typename S1, typename S2>
 void printComparisonError(const std::string& comparison_type,
                           const S1& s1, const Transform3f& tf1,
                           const S2& s2, const Transform3f& tf2,
-                          GJKSolverType solver_type,
                           const Vec3f& contact_or_normal,
                           const Vec3f& expected_contact_or_normal,
                           bool check_opposite_normal,
@@ -72,8 +71,7 @@ void printComparisonError(const std::string& comparison_type,
   std::cout << "Disagreement between " << comparison_type
             << " and expected_" << comparison_type << " for "
             << getNodeTypeName(s1.getNodeType()) << " and "
-            << getNodeTypeName(s2.getNodeType()) << " with '"
-            << getGJKSolverName(solver_type) << "' solver." << std::endl
+            << getNodeTypeName(s2.getNodeType()) << ".\n"
             << "tf1.quaternion: " << tf1.getQuatRotation() << std::endl
             << "tf1.translation: " << tf1.getTranslation().transpose() << std::endl
             << "tf2.quaternion: " << tf2.getQuatRotation() << std::endl
@@ -93,7 +91,6 @@ template <typename S1, typename S2>
 void printComparisonError(const std::string& comparison_type,
                           const S1& s1, const Transform3f& tf1,
                           const S2& s2, const Transform3f& tf2,
-                          GJKSolverType solver_type,
                           FCL_REAL depth,
                           FCL_REAL expected_depth,
                           FCL_REAL tol)
@@ -101,8 +98,7 @@ void printComparisonError(const std::string& comparison_type,
   std::cout << "Disagreement between " << comparison_type
             << " and expected_" << comparison_type << " for "
             << getNodeTypeName(s1.getNodeType()) << " and "
-            << getNodeTypeName(s2.getNodeType()) << " with '"
-            << getGJKSolverName(solver_type) << "' solver." << std::endl
+            << getNodeTypeName(s2.getNodeType()) << ".\n"
             << "tf1.quaternion: " << tf1.getQuatRotation() << std::endl
             << "tf1.translation: " << tf1.getTranslation() << std::endl
             << "tf2.quaternion: " << tf2.getQuatRotation() << std::endl
@@ -116,7 +112,6 @@ void printComparisonError(const std::string& comparison_type,
 template <typename S1, typename S2>
 void compareContact(const S1& s1, const Transform3f& tf1,
                     const S2& s2, const Transform3f& tf2,
-                    GJKSolverType solver_type,
                     const Vec3f& contact, Vec3f* expected_point,
                     FCL_REAL depth, FCL_REAL* expected_depth,
                     const Vec3f& normal, Vec3f* expected_normal, bool check_opposite_normal,
@@ -127,7 +122,7 @@ void compareContact(const S1& s1, const Transform3f& tf1,
     bool contact_equal = isEqual(contact, *expected_point, tol);
     BOOST_CHECK(contact_equal);
     if (!contact_equal)
-      printComparisonError("contact", s1, tf1, s2, tf2, solver_type, contact, *expected_point, false, tol);
+      printComparisonError("contact", s1, tf1, s2, tf2, contact, *expected_point, false, tol);
   }
 
   if (expected_depth)
@@ -135,7 +130,7 @@ void compareContact(const S1& s1, const Transform3f& tf1,
     bool depth_equal = std::fabs(depth - *expected_depth) < tol;
     BOOST_CHECK(depth_equal);
     if (!depth_equal)
-      printComparisonError("depth", s1, tf1, s2, tf2, solver_type, depth, *expected_depth, tol);
+      printComparisonError("depth", s1, tf1, s2, tf2, depth, *expected_depth, tol);
   }
 
   if (expected_normal)
@@ -147,14 +142,13 @@ void compareContact(const S1& s1, const Transform3f& tf1,
 
     BOOST_CHECK(normal_equal);
     if (!normal_equal)
-      printComparisonError("normal", s1, tf1, s2, tf2, solver_type, normal, *expected_normal, check_opposite_normal, tol);
+      printComparisonError("normal", s1, tf1, s2, tf2, normal, *expected_normal, check_opposite_normal, tol);
   }
 }
 
 template <typename S1, typename S2>
 void testShapeIntersection(const S1& s1, const Transform3f& tf1,
                            const S2& s2, const Transform3f& tf2,
-                           GJKSolverType solver_type,
                            bool expected_res,
                            Vec3f* expected_point = NULL,
                            FCL_REAL* expected_depth = NULL,
@@ -163,7 +157,6 @@ void testShapeIntersection(const S1& s1, const Transform3f& tf1,
                            FCL_REAL tol = 1e-9)
 {
   CollisionRequest request;
-  request.gjk_solver_type = solver_type;
   CollisionResult result;
 
   Vec3f contact;
@@ -185,7 +178,7 @@ void testShapeIntersection(const S1& s1, const Transform3f& tf1,
     if (result.numContacts() == 1)
     {
       Contact contact = result.getContact(0);
-      compareContact(s1, tf1, s2, tf2, solver_type, contact.pos, expected_point, contact.penetration_depth, expected_depth, contact.normal, expected_normal, check_opposite_normal, tol);
+      compareContact(s1, tf1, s2, tf2, contact.pos, expected_point, contact.penetration_depth, expected_depth, contact.normal, expected_normal, check_opposite_normal, tol);
     }
   }
 }
@@ -299,69 +292,69 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_spheresphere)
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(40, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(40, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(30, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(30.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(30.01, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(29.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(29.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f();
   normal.setZero();  // If the centers of two sphere are at the same position, the normal is (0, 0, 0)
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform;
   normal.setZero();  // If the centers of two sphere are at the same position, the normal is (0, 0, 0)
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-29.9, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-29.9, 0, 0));
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-30.0, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-30.01, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-30.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 bool compareContactPoints(const Vec3f& c1,const Vec3f& c2)
@@ -434,32 +427,32 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_boxbox)
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position. The current result is (1, 0, 0).
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position. The current result is (1, 0, 0).
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(15, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(15.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(q);
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = transform;
   tf2 = transform * Transform3f(q);
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   FCL_UINT32 numTests = 1e+2;
   for (FCL_UINT32 i = 0; i < numTests; ++i)
@@ -489,30 +482,30 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_spherebox)
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position. The current result is (-1, 0, 0).
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(22.50001, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(22.501, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(22.4, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(22.4, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_spherecapsule)
@@ -533,42 +526,42 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_spherecapsule)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(24.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(24.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(25, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(24.999999, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(25.1, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(25.1, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_cylindercylinder)
@@ -589,35 +582,35 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_cylindercylinder)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 9.9, 0));
   normal << 0, 1, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 /*
@@ -639,40 +632,40 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_conecone)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, tol_gjk);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.001, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.001, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 9.9));
   normal << 0, 0, 1;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 9.9));
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 }
 */
 
@@ -695,48 +688,48 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_conecylinder)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 0.061);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 0.061);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 0.46);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 0.46);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 9.9));
   normal << 0, 0, 1;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 9.9));
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10.01));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.01));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 */
 
@@ -912,64 +905,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacesphere)
   contact << -5, 0, 0;
   depth = 10;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(-5, 0, 0));
   depth = 10;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5, 0, 0));
   contact << -2.5, 0, 0;
   depth = 15;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5, 0, 0));
   contact = transform.transform(Vec3f(-2.5, 0, 0));
   depth = 15;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5, 0, 0));
   contact << -7.5, 0, 0;
   depth = 5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5, 0, 0));
   contact = transform.transform(Vec3f(-7.5, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = 20.1;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.1, 0, 0));
   contact = transform.transform(Vec3f(0.05, 0, 0));
   depth = 20.1;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_planesphere)
@@ -992,58 +985,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planesphere)
   contact.setZero();
   depth = 10;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 10;
   normal = transform.getRotation() * Vec3f(1, 0, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5, 0, 0));
   contact << 5, 0, 0;
   depth = 5;
   normal << 1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5, 0, 0));
   contact = transform.transform(Vec3f(5, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5, 0, 0));
   contact << -5, 0, 0;
   depth = 5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5, 0, 0));
   contact = transform.transform(Vec3f(-5, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacebox)
@@ -1066,68 +1059,68 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacebox)
   contact << -1.25, 0, 0;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(-1.25, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(1.25, 0, 0));
   contact << -0.625, 0, 0;
   depth = 3.75;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(1.25, 0, 0));
   contact = transform.transform(Vec3f(-0.625, 0, 0));
   depth = 3.75;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-1.25, 0, 0));
   contact << -1.875, 0, 0;
   depth = 1.25;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-1.25, 0, 0));
   contact = transform.transform(Vec3f(-1.875, 0, 0));
   depth = 1.25;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.51, 0, 0));
   contact << 0.005, 0, 0;
   depth = 5.01;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.51, 0, 0));
   contact = transform.transform(Vec3f(0.005, 0, 0));
   depth = 5.01;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f(transform.getRotation());
   tf2 = Transform3f();
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true);
+  testShapeIntersection(s, tf1, hs, tf2, true);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_planebox)
@@ -1150,62 +1143,62 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planebox)
   contact << 0, 0, 0;
   depth = 2.5;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(1.25, 0, 0));
   contact << 1.25, 0, 0;
   depth = 1.25;
   normal << 1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(1.25, 0, 0));
   contact = transform.transform(Vec3f(1.25, 0, 0));
   depth = 1.25;
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-1.25, 0, 0));
   contact << -1.25, 0, 0;
   depth = 1.25;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-1.25, 0, 0));
   contact = transform.transform(Vec3f(-1.25, 0, 0));
   depth = 1.25;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.51, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f(transform.getRotation());
   tf2 = Transform3f();
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true);
+  testShapeIntersection(s, tf1, hs, tf2, true);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecapsule)
@@ -1228,64 +1221,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecapsule)
   contact << -2.5, 0, 0;
   depth = 5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(-2.5, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << -1.25, 0, 0;
   depth = 7.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(-1.25, 0, 0));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -3.75, 0, 0;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-3.75, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = 10.1;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
   contact = transform.transform(Vec3f(0.05, 0, 0));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1297,64 +1290,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecapsule)
   contact << 0, -2.5, 0;
   depth = 5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, -2.5, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, -1.25, 0;
   depth = 7.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, -1.25, 0));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -3.75, 0;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -3.75, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
   contact << 0, 0.05, 0;
   depth = 10.1;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
   contact = transform.transform(Vec3f(0, 0.05, 0));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1366,64 +1359,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecapsule)
   contact << 0, 0, -5;
   depth = 10;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, -5));
   depth = 10;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, -3.75;
   depth = 12.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, -3.75));
   depth = 12.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -6.25;
   depth = 7.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
   contact = transform.transform(Vec3f(0, 0, -6.25));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10.1));
   contact << 0, 0, 0.05;
   depth = 20.1;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.1));
   contact = transform.transform(Vec3f(0, 0, 0.05));
   depth = 20.1;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
@@ -1446,58 +1439,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   contact << 0, 0, 0;
   depth = 5;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, 0x0, 0x0, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, 0x0, 0x0, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, 0x0, 0x0, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, 0x0, 0x0, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << 2.5, 0, 0;
   depth = 2.5;
   normal << 1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(2.5, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -2.5, 0, 0;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-2.5, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1510,7 +1503,7 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   depth = 5;
   normal << 0, 1, 0;  // (0, 1, 0) or (0, -1, 0)
   testShapeIntersection
-    (s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0, true);
+    (s, tf1, hs, tf2, true, 0x0, &depth, 0x0, true);
 
   tf1 = transform;
   tf2 = transform;
@@ -1518,51 +1511,51 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);  // (0, 1, 0) or (0, -1, 0)
   testShapeIntersection
-    (s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal, true);
+    (s, tf1, hs, tf2, true, 0x0, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, 2.5, 0;
   depth = 2.5;
   normal << 0, 1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, 2.5, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -2.5, 0;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -2.5, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1574,7 +1567,7 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   contact << 0, 0, 0;
   depth = 10;
   normal << 0, 0, 1;  // (0, 0, 1) or (0, 0, -1)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, 0x0, 0x0, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, 0x0, 0x0, true);
 
   tf1 = transform;
   tf2 = transform;
@@ -1582,28 +1575,28 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   depth = 10;
   normal = transform.getRotation() * Vec3f(0, 0, 1);  // (0, 0, 1) or (0, 0, -1)
   testShapeIntersection
-    (s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0, true);
+    (s, tf1, hs, tf2, true, 0x0, &depth, 0x0, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, 2.5;
   depth = 7.5;
   normal << 0, 0, 1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, 2.5));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -2.5;
   depth = 7.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+  testShapeIntersection(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
@@ -1611,23 +1604,23 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule)
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
   testShapeIntersection
-    (s, tf1, hs, tf2, GST_INDEP, true, 0x0, &depth, 0x0);
+    (s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecylinder)
@@ -1650,64 +1643,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecylinder)
   contact << -2.5, 0, 0;
   depth = 5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(-2.5, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << -1.25, 0, 0;
   depth = 7.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(-1.25, 0, 0));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -3.75, 0, 0;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-3.75, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = 10.1;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
   contact = transform.transform(Vec3f(0.05, 0, 0));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1719,64 +1712,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecylinder)
   contact << 0, -2.5, 0;
   depth = 5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, -2.5, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, -1.25, 0;
   depth = 7.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, -1.25, 0));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -3.75, 0;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -3.75, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
   contact << 0, 0.05, 0;
   depth = 10.1;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
   contact = transform.transform(Vec3f(0, 0.05, 0));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1788,64 +1781,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecylinder)
   contact << 0, 0, -2.5;
   depth = 5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, -2.5));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, -1.25;
   depth = 7.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, -1.25));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -3.75;
   depth = 2.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
   contact = transform.transform(Vec3f(0, 0, -3.75));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 5.1));
   contact << 0, 0, 0.05;
   depth = 10.1;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 5.1));
   contact = transform.transform(Vec3f(0, 0, 0.05));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -5.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -5.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_planecylinder)
@@ -1868,58 +1861,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecylinder)
   contact << 0, 0, 0;
   depth = 5;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << 2.5, 0, 0;
   depth = 2.5;
   normal << 1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(2.5, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -2.5, 0, 0;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-2.5, 0, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1931,58 +1924,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecylinder)
   contact << 0, 0, 0;
   depth = 5;
   normal << 0, 1, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, 2.5, 0;
   depth = 2.5;
   normal << 0, 1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, 2.5, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -2.5, 0;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -2.5, 0));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -1994,58 +1987,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecylinder)
   contact << 0, 0, 0;
   depth = 5;
   normal << 0, 0, 1;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 0, 1);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, 2.5;
   depth = 2.5;
   normal << 0, 0, 1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, 2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -2.5;
   depth = 2.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
   contact = transform.transform(Vec3f(0, 0, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 
@@ -2069,64 +2062,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecone)
   contact << -2.5, 0, -5;
   depth = 5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(-2.5, 0, -5));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << -1.25, 0, -5;
   depth = 7.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(-1.25, 0, -5));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -3.75, 0, -5;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-3.75, 0, -5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
   contact << 0.05, 0, -5;
   depth = 10.1;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
   contact = transform.transform(Vec3f(0.05, 0, -5));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -2138,64 +2131,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecone)
   contact << 0, -2.5, -5;
   depth = 5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, -2.5, -5));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, -1.25, -5;
   depth = 7.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, -1.25, -5));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -3.75, -5;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -3.75, -5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
   contact << 0, 0.05, -5;
   depth = 10.1;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
   contact = transform.transform(Vec3f(0, 0.05, -5));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -2207,64 +2200,64 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecone)
   contact << 0, 0, -2.5;
   depth = 5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, -2.5));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, -1.25;
   depth = 7.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, -1.25));
   depth = 7.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -3.75;
   depth = 2.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
   contact = transform.transform(Vec3f(0, 0, -3.75));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 5.1));
   contact << 0, 0, 0.05;
   depth = 10.1;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 5.1));
   contact = transform.transform(Vec3f(0, 0, 0.05));
   depth = 10.1;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -5.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -5.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersection_planecone)
@@ -2287,58 +2280,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecone)
   contact << 0, 0, 0;
   depth = 5;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(2.5, 0, 0));
   contact << 2.5, 0, -2.5;
   depth = 2.5;
   normal << 1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(2.5, 0, 0));
   contact = transform.transform(Vec3f(2.5, 0, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-2.5, 0, 0));
   contact << -2.5, 0, -2.5;
   depth = 2.5;
   normal << -1, 0, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-2.5, 0, 0));
   contact = transform.transform(Vec3f(-2.5, 0, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-5.1, 0, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -2350,58 +2343,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecone)
   contact << 0, 0, 0;
   depth = 5;
   normal << 0, 1, 0;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 2.5, 0));
   contact << 0, 2.5, -2.5;
   depth = 2.5;
   normal << 0, 1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 2.5, 0));
   contact = transform.transform(Vec3f(0, 2.5, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -2.5, 0));
   contact << 0, -2.5, -2.5;
   depth = 2.5;
   normal << 0, -1, 0;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -2.5, 0));
   contact = transform.transform(Vec3f(0, -2.5, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, -1, 0);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, -5.1, 0));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
 
 
@@ -2413,58 +2406,58 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_planecone)
   contact << 0, 0, 0;
   depth = 5;
   normal << 0, 0, 1;  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = transform;
   tf2 = transform;
   contact = transform.transform(Vec3f(0, 0, 0));
   depth = 5;
   normal = transform.getRotation() * Vec3f(0, 0, 1);  // (1, 0, 0) or (-1, 0, 0)
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal, true);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 2.5));
   contact << 0, 0, 2.5;
   depth = 2.5;
   normal << 0, 0, 1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 2.5));
   contact = transform.transform(Vec3f(0, 0, 2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -2.5));
   contact << 0, 0, -2.5;
   depth = 2.5;
   normal << 0, 0, -1;
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -2.5));
   contact = transform.transform(Vec3f(0, 0, -2.5));
   depth = 2.5;
   normal = transform.getRotation() * Vec3f(0, 0, -1);
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, true, &contact, &depth, &normal);
+  testShapeIntersection(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, -10.1));
-  testShapeIntersection(s, tf1, hs, tf2, GST_INDEP, false);
+  testShapeIntersection(s, tf1, hs, tf2, false);
 }
 
 
@@ -2854,69 +2847,69 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spheresphere)
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(40, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(40, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(30, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(30.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(30.01, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(29.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(29.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f();
   normal.setZero();  // If the centers of two sphere are at the same position, the normal is (0, 0, 0)
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform;
   normal.setZero();  // If the centers of two sphere are at the same position, the normal is (0, 0, 0)
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-29.9, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-29.9, 0, 0));
   normal = transform.getRotation() * Vec3f(-1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-30.0, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(-30.01, 0, 0));
   normal << -1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(-30.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_boxbox)
@@ -2941,32 +2934,32 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_boxbox)
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position. The current result is (1, 0, 0).
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position. The current result is (1, 0, 0).
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(15, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(15.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(q);
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = transform;
   tf2 = transform * Transform3f(q);
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, 0x0);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spherebox)
@@ -2987,33 +2980,33 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spherebox)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(22.5, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 1e-7);  // built-in GJK solver requires larger tolerance than libccd
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 1e-7);  // built-in GJK solver requires larger tolerance than libccd
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(22.51, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(22.4, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 1e-2);  // built-in GJK solver requires larger tolerance than libccd
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 1e-2);  // built-in GJK solver requires larger tolerance than libccd
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(22.4, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
   // built-in GJK solver returns incorrect normal.
-  // testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  // testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spherecapsule)
@@ -3034,32 +3027,32 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spherecapsule)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(24.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(24.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(25, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(25.1, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_cylindercylinder)
@@ -3080,33 +3073,33 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_cylindercylinder)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 3e-1);  // built-in GJK solver requires larger tolerance than libccd
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 3e-1);  // built-in GJK solver requires larger tolerance than libccd
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true);
+  testShapeIntersection(s1, tf1, s2, tf2, true);
   // built-in GJK solver returns incorrect normal.
-  // testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  // testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.01, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecone)
@@ -3127,44 +3120,44 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecone)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
   normal << 1, 0, 0;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal, false, 5.7e-1);  // built-in GJK solver requires larger tolerance than libccd
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 5.7e-1);  // built-in GJK solver requires larger tolerance than libccd
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
   normal = transform.getRotation() * Vec3f(1, 0, 0);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
   // built-in GJK solver returns incorrect normal.
-  // testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  // testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10.1, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10.1, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 9.9));
   normal << 0, 0, 1;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 9.9));
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
   // built-in GJK solver returns incorrect normal.
-  // testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  // testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 }
 
 BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecylinder)
@@ -3185,49 +3178,49 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecylinder)
   tf1 = Transform3f();
   tf2 = Transform3f();
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform;
   // TODO: Need convention for normal when the centers of two objects are at same position.
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(9.9, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(9.9, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(10, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(10, 0, 0));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 9.9));
   normal << 0, 0, 1;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 9.9));
   normal = transform.getRotation() * Vec3f(0, 0, 1);
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, NULL);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
   // built-in GJK solver returns incorrect normal.
-  // testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  // testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = Transform3f();
   tf2 = Transform3f(Vec3f(0, 0, 10));
   normal << 0, 0, 1;
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, true, NULL, NULL, &normal);
+  testShapeIntersection(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
   tf2 = transform * Transform3f(Vec3f(0, 0, 10.1));
-  testShapeIntersection(s1, tf1, s2, tf2, GST_INDEP, false);
+  testShapeIntersection(s1, tf1, s2, tf2, false);
 }
 
 
diff --git a/test/shape_mesh_consistency.cpp b/test/shape_mesh_consistency.cpp
index 226f15898e91ddccbabef13a2804f26f9e653920..7e5bb18210b2ad747a3494005512b80650036b2c 100644
--- a/test/shape_mesh_consistency.cpp
+++ b/test/shape_mesh_consistency.cpp
@@ -428,7 +428,6 @@ BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_GJK)
   generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
 
   DistanceRequest request;
-  request.gjk_solver_type = GST_INDEP;
   DistanceResult res, res1;
 
   Transform3f pose;
@@ -1507,7 +1506,6 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK)
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
   CollisionRequest request (false, 1, false);
-  request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
 
@@ -1727,7 +1725,6 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK)
   generateBVHModel(s2_obb, s2, Transform3f());
 
   CollisionRequest request (false, 1, false);
-  request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
 
@@ -1849,7 +1846,6 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK)
   generateBVHModel(s2_obb, s2, Transform3f());
 
   CollisionRequest request (false, 1, false);
-  request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
 
@@ -1971,7 +1967,6 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK)
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
   CollisionRequest request (false, 1, false);
-  request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
 
@@ -2060,7 +2055,6 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK)
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
   CollisionRequest request (false, 1, false);
-  request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
 
diff --git a/test/utility.cpp b/test/utility.cpp
index ca0debf7f1d5a97ebb27dcd39f25b0cac01c1884..d3590d91c957b7c7f8bdad6d47877b41814b955e 100644
--- a/test/utility.cpp
+++ b/test/utility.cpp
@@ -417,14 +417,6 @@ std::string getNodeTypeName(NODE_TYPE node_type)
     return std::string("invalid");
 }
 
-std::string getGJKSolverName(GJKSolverType solver_type)
-{
-  if (solver_type == GST_INDEP)
-    return std::string("built-in");
-  else
-    return std::string("invalid");
-}
-
 Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z)
 {
   Quaternion3f q;
diff --git a/test/utility.h b/test/utility.h
index 97b3b3355c18ea7929569e361fc758e7d352edaf..d51e4285c9b236236acc38107dedc91d6f396042 100644
--- a/test/utility.h
+++ b/test/utility.h
@@ -172,8 +172,6 @@ bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2, void* cda
 
 std::string getNodeTypeName(NODE_TYPE node_type);
 
-std::string getGJKSolverName(GJKSolverType solver_type);
-
 Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z);
 
 std::ostream& operator<< (std::ostream& os, const Transform3f& tf);