diff --git a/include/hpp/fcl/collision_data.h b/include/hpp/fcl/collision_data.h
index d940292ad3c72096af89090be1e210011f5c13b7..002e0781a2577d21b3c44d17a55dc9536e3be3a0 100644
--- a/include/hpp/fcl/collision_data.h
+++ b/include/hpp/fcl/collision_data.h
@@ -164,11 +164,15 @@ struct CollisionRequest
                    size_t num_max_cost_sources_ = 1,
                    bool enable_cost_ = false,
                    bool use_approximate_cost_ = true,
-                   GJKSolverType gjk_solver_type_ = GST_INDEP) :
-  num_max_contacts(num_max_contacts_),
+                   GJKSolverType gjk_solver_type_ = GST_INDEP)
+  HPP_FCL_DEPRECATED;
+
+  CollisionRequest(bool enable_contact_, size_t num_max_contacts_,
+		   bool enable_distance_lower_bound_) :
+    num_max_contacts(num_max_contacts_),
     enable_contact(enable_contact_),
     enable_distance_lower_bound (enable_distance_lower_bound_),
-    gjk_solver_type(gjk_solver_type_),
+    gjk_solver_type(GST_INDEP),
     security_margin (0),
     break_distance (1e-3)
   {
diff --git a/src/collision_data.cpp b/src/collision_data.cpp
index db087d0acacbe20f52b6d59cb04c5738a5dd3f27..2875d6c93ba647ffababb7622104d7dc8d55a989 100644
--- a/src/collision_data.cpp
+++ b/src/collision_data.cpp
@@ -50,4 +50,19 @@ bool DistanceRequest::isSatisfied(const DistanceResult& result) const
   return (result.min_distance <= 0);
 }
 
+  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_) :
+    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)
+  {
+    enable_cached_gjk_guess = false;
+    cached_gjk_guess = Vec3f(1, 0, 0);
+  }
 }
diff --git a/test/benchmark.cpp b/test/benchmark.cpp
index 28571253dd744714640da7a471bef6fca8abeb71..eae31f235e24fc86c8316cab8f11af7be1a625f2 100644
--- a/test/benchmark.cpp
+++ b/test/benchmark.cpp
@@ -117,8 +117,8 @@ double collide (const std::vector<Transform3f>& tf,
   Transform3f pose2;
 
   CollisionResult local_result;	
-  CollisionRequest request;
-  TraversalNode node(false);
+  CollisionRequest request (false, 1, false);
+  TraversalNode node (request);
 
   node.enable_statistics = verbose;
 
@@ -129,7 +129,6 @@ double collide (const std::vector<Transform3f>& tf,
     bool success (initialize(node, m1, tf[i], m2, pose2, local_result));
     assert (success);
 
-    CollisionRequest request (1, true, true);
     CollisionResult result;
     collide(&node, request, result);
   }
diff --git a/test/general_test.cpp b/test/general_test.cpp
index e8edfb0459f45442489d01ebc977fa99e4a031d7..110bae2ff24d8d98d2a60b2ebf6005983c3e2a9e 100644
--- a/test/general_test.cpp
+++ b/test/general_test.cpp
@@ -36,8 +36,7 @@ int main(int argc, char** argv)
   static const int num_max_contacts = std::numeric_limits<int>::max();
   static const bool enable_contact = true;
   fcl::CollisionResult result;
-  fcl::CollisionRequest request(num_max_contacts,
-                                enable_contact);
+  fcl::CollisionRequest request(enable_contact, num_max_contacts, false);
 
 
   CollisionObject co0(box0, tf0);
@@ -51,4 +50,4 @@ int main(int argc, char** argv)
   BOOST_FOREACH(Contact& contact, contacts) {
     cout << "position: " << contact.pos << endl;
   }
-}
\ No newline at end of file
+}
diff --git a/test/test_fcl_collision.cpp b/test/test_fcl_collision.cpp
index 18328ea80639ba88e0b54cafd91dc0718d6c1db3..f5c98fc145a13024e5268ed0e70a1d31378e3756 100644
--- a/test/test_fcl_collision.cpp
+++ b/test/test_fcl_collision.cpp
@@ -833,7 +833,7 @@ bool collide_Test2(const Transform3f& tf,
   Transform3f pose1, pose2;
 
   CollisionResult local_result;
-  CollisionRequest request (num_max_contacts, enable_contact);
+  CollisionRequest request (enable_contact, num_max_contacts, false);
   MeshCollisionTraversalNode<BV> node (request);
 
   bool success = initialize <BV> (node, m1, pose1, m2, pose2, local_result);
@@ -891,7 +891,7 @@ bool collide_Test(const Transform3f& tf,
   Transform3f pose1(tf), pose2;
 
   CollisionResult local_result;
-  CollisionRequest request (num_max_contacts, enable_contact);
+  CollisionRequest request (enable_contact, num_max_contacts, false);
   MeshCollisionTraversalNode<BV> node (request);
 
   bool success = initialize <BV> (node, m1, pose1, m2, pose2, local_result);
@@ -948,7 +948,7 @@ bool collide_Test_Oriented(const Transform3f& tf,
   Transform3f pose1(tf), pose2;
 
   CollisionResult local_result;
-  CollisionRequest request (num_max_contacts, enable_contact);
+  CollisionRequest request (enable_contact, num_max_contacts, false);
   TraversalNode node (request);
   bool success = initialize (node, (const BVHModel<BV>&)m1, pose1,
                              (const BVHModel<BV>&)m2, pose2, local_result);
@@ -1007,7 +1007,7 @@ bool test_collide_func(const Transform3f& tf,
 
   std::vector<Contact> contacts;
 
-  CollisionRequest request(num_max_contacts, enable_contact);
+  CollisionRequest request (enable_contact, num_max_contacts, false);
   CollisionResult result;
   int num_contacts = collide(&m1, pose1, &m2, pose2, 
                              request, result);
diff --git a/test/test_fcl_distance.cpp b/test/test_fcl_distance.cpp
index ea98c723235239ec95bd71c0cda32e2d717c465d..891f091efa539e8cb3f191194fc8c6cba10c5191 100644
--- a/test/test_fcl_distance.cpp
+++ b/test/test_fcl_distance.cpp
@@ -413,7 +413,7 @@ bool collide_Test_OBB(const Transform3f& tf,
   m2.endModel();
 
   CollisionResult local_result;
-  CollisionRequest request (1, true, true);
+  CollisionRequest request (true, 1, true);
   MeshCollisionTraversalNodeOBB node (request);
   bool success (initialize(node, (const BVHModel<OBB>&)m1, tf,
                            (const BVHModel<OBB>&)m2, Transform3f(),
diff --git a/test/test_fcl_distance_lower_bound.cpp b/test/test_fcl_distance_lower_bound.cpp
index b7758b1b09aa073ad925f5e7301bfecca9973201..3f80a035d385114a189f1fd59d10031038a64d61 100644
--- a/test/test_fcl_distance_lower_bound.cpp
+++ b/test/test_fcl_distance_lower_bound.cpp
@@ -68,7 +68,7 @@ bool testDistanceLowerBound (const Transform3f& tf,
 {
   Transform3f pose1(tf), pose2;
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.enable_distance_lower_bound = true;
 
   CollisionResult result;
@@ -86,7 +86,7 @@ bool testCollide (const Transform3f& tf, const CollisionGeometryPtr_t& m1,
 {
   Transform3f pose1(tf), pose2;
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.enable_distance_lower_bound = false;
 
   CollisionResult result;
@@ -141,7 +141,6 @@ BOOST_AUTO_TEST_CASE(mesh_mesh)
   std::vector<Transform3f> transforms;
   FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
   std::size_t n = 100;
-  bool verbose = false;
 
   generateRandomTransforms(extents, transforms, n);
 
diff --git a/test/test_fcl_frontlist.cpp b/test/test_fcl_frontlist.cpp
index 831c26a9071be4876445c38a2b145327450da904..7845d40b68dff381d51d1d214965c21f4652d841 100644
--- a/test/test_fcl_frontlist.cpp
+++ b/test/test_fcl_frontlist.cpp
@@ -229,7 +229,7 @@ bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
   Transform3f pose1, pose2;
 
   CollisionResult local_result;
-  CollisionRequest request (std::numeric_limits<int>::max(), false);
+  CollisionRequest request (false, std::numeric_limits<int>::max());
   MeshCollisionTraversalNode<BV> node (request);
 
   bool success = initialize <BV>(node, m1, pose1, m2, pose2, local_result);
@@ -292,7 +292,7 @@ bool collide_front_list_Test_Oriented(const Transform3f& tf1, const Transform3f&
   Transform3f pose1(tf1), pose2;
 
   CollisionResult local_result;	
-  CollisionRequest request (std::numeric_limits<int>::max(), false);
+  CollisionRequest request (false, std::numeric_limits<int>::max());
   TraversalNode node (request);
 
   bool success = initialize (node, (const BVHModel<BV>&)m1, pose1,
@@ -343,7 +343,7 @@ bool collide_Test(const Transform3f& tf,
   Transform3f pose1(tf), pose2;
 
   CollisionResult local_result;
-  CollisionRequest request (std::numeric_limits<int>::max(), false);
+  CollisionRequest request (false, std::numeric_limits<int>::max());
   MeshCollisionTraversalNode<BV> node (request);
 
   bool success = initialize <BV>(node, m1, pose1, m2, pose2, local_result);
diff --git a/test/test_fcl_profiling.cpp b/test/test_fcl_profiling.cpp
index b02f679f46719bff5a3b2b91a916636415b81248..1a2f1e1bcdd13af33ff7b2be93f82d38f3b459e3 100644
--- a/test/test_fcl_profiling.cpp
+++ b/test/test_fcl_profiling.cpp
@@ -228,14 +228,7 @@ int main(int argc, char** argv)
   
   std::vector<Transform3f> transforms;
 
-  CollisionRequest request;
-  // request.num_max_contacts = 1;
-  // request.enable_contact = false;
-  // request.enable_distance_lower_bound = false;
-  // request.num_max_cost_sources = 1;
-  // request.enable_cost = false;
-  // request.use_approximate_cost = true;
-  // request.gjk_solver_type = GST_INDEP;
+  CollisionRequest request (false, 1, false);
 
   if (argc > 1) {
     int iarg = 1;
diff --git a/test/test_fcl_shape_mesh_consistency.cpp b/test/test_fcl_shape_mesh_consistency.cpp
index e527ff3c013bf13dcf1223fefd3a2a491bd7f02d..daa2bb5a884df5ee8c7d2db8567d150d41fc588e 100644
--- a/test/test_fcl_shape_mesh_consistency.cpp
+++ b/test/test_fcl_shape_mesh_consistency.cpp
@@ -808,7 +808,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_libccd)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   CollisionResult result;
 
   bool res;
@@ -1026,7 +1026,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_libccd)
   generateBVHModel(s1_obb, s1, Transform3f());
   generateBVHModel(s2_obb, s2, Transform3f());
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   CollisionResult result;
 
   bool res;
@@ -1146,7 +1146,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_libccd)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f());
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   CollisionResult result;
 
   bool res;
@@ -1266,7 +1266,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_libccd)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   CollisionResult result;
 
   bool res;
@@ -1353,7 +1353,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_libccd)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   CollisionResult result;
 
   bool res;
@@ -1506,7 +1506,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
@@ -1726,7 +1726,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK)
   generateBVHModel(s1_obb, s1, Transform3f());
   generateBVHModel(s2_obb, s2, Transform3f());
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
@@ -1848,7 +1848,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f());
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
@@ -1970,7 +1970,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
@@ -2059,7 +2059,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK)
   generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
   generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
 
-  CollisionRequest request;
+  CollisionRequest request (false, 1, false);
   request.gjk_solver_type = GST_INDEP;
 
   CollisionResult result;
diff --git a/test/test_fcl_utility.h b/test/test_fcl_utility.h
index db297b8d1ca039f4e46841cf78310304835bdbb6..de55a35b6a522639f32cdbe73f955186eac7b30a 100644
--- a/test/test_fcl_utility.h
+++ b/test/test_fcl_utility.h
@@ -113,7 +113,7 @@ struct DistanceRes
 /// @brief Collision data stores the collision request and the result given by collision algorithm. 
 struct CollisionData
 {
-  CollisionData()
+CollisionData() : request (false, 1, false)
   {
     done = false;
   }