diff --git a/README.md b/README.md
index 7cb262f3da5108d24b47c556e1a07a57108a72ba..d731a17273289c6accc29f1391adf24d10464b05 100644
--- a/README.md
+++ b/README.md
@@ -111,10 +111,10 @@ int main() {
   std::shared_ptr<hpp::fcl::ConvexBase> shape2 = loadConvexMesh("../path/to/mesh/file.obj");
 
   // Define the shapes' placement in 3D space
-  hpp::fcl::Transform3f T1;
+  hpp::fcl::Transform3s T1;
   T1.setQuatRotation(hpp::fcl::Quaternion3f::UnitRandom());
   T1.setTranslation(hpp::fcl::Vec3s::Random());
-  hpp::fcl::Transform3f T2 = hpp::fcl::Transform3f::Identity();
+  hpp::fcl::Transform3s T2 = hpp::fcl::Transform3s::Identity();
   T2.setQuatRotation(hpp::fcl::Quaternion3f::UnitRandom());
   T2.setTranslation(hpp::fcl::Vec3s::Random());
 
@@ -180,10 +180,10 @@ if __name__ == "__main__":
     shape2 = loadConvexMesh("../path/to/mesh/file.obj")
 
     # Define the shapes' placement in 3D space
-    T1 = hppfcl.Transform3f()
+    T1 = hppfcl.Transform3s()
     T1.setTranslation(pin.SE3.Random().translation)
     T1.setRotation(pin.SE3.Random().rotation)
-    T2 = hppfcl.Transform3f();
+    T2 = hppfcl.Transform3s();
     # Using np arrays also works
     T1.setTranslation(np.random.rand(3))
     T2.setRotation(pin.SE3.Random().rotation)
diff --git a/doc/mesh-mesh-collision-call.dot b/doc/mesh-mesh-collision-call.dot
index 5069bbc495f2d6912bfa5c22071ec53ec997a225..e70206145a73c478061f5572ef1758baf2dc7460 100644
--- a/doc/mesh-mesh-collision-call.dot
+++ b/doc/mesh-mesh-collision-call.dot
@@ -4,7 +4,7 @@ digraph CD  {
 	compound=true
         size = 11.7
 
-        "std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3f& tf1, const CollisionGeometry* o2,\nconst Transform3f& tf2, const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
+        "std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
         "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" [shape = box]
         "bool OBBRSS::overlap(const OBBRSS& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" [shape = box]
         "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)" [shape = box]
@@ -19,7 +19,7 @@ digraph CD  {
         "MeshCollisionTraversalNode<T_BVH>::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n  -request\n  - result" [shape = box]
         "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)" [shape = box]
 
-         "std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3f& tf1, const CollisionGeometry* o2,\nconst Transform3f& tf2, const CollisionRequest& request,\nCollisionResult& result)" -> "void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"
+         "std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" -> "void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"
         "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)"
         "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)"
         "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)"
diff --git a/doc/shape-mesh-collision-call.dot b/doc/shape-mesh-collision-call.dot
index 3eb293642b3bbe0cf0af2d9a602643b6dfff2404..2a16e9f98ffcb57d46b012e5d67567f539ab1d4e 100644
--- a/doc/shape-mesh-collision-call.dot
+++ b/doc/shape-mesh-collision-call.dot
@@ -4,8 +4,8 @@ digraph CD  {
 	compound=true
         size = 11.7
 
-        "BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
-        "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
+        "BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
+        "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
         "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" [shape = box]
         "void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" [shape = box]
         "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" [shape = box]
@@ -16,11 +16,11 @@ digraph CD  {
         "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" [shape = box]
         "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp" [shape = box]
         "bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nCoalScalar& squaredLowerBoundDistance)\nBV/OBB.cpp" [shape = box]
-        "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3f& tf1,\nconst Transform3f& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" [shape = box]
-        "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3f& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156" [shape = box]
+        "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" [shape = box]
+        "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156" [shape = box]
 
-        "BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" -> "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp"
-        "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" -> "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp"
+        "BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" -> "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp"
+        "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" -> "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp"
         "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp"
         "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
         "void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
@@ -31,6 +31,6 @@ digraph CD  {
         "bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp"
         "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp"
         "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp" -> "bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nCoalScalar& squaredLowerBoundDistance)\nBV/OBB.cpp"
-        "bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3f& tf1,\nconst Transform3f& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293"
-        "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3f& tf1,\nconst Transform3f& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" -> "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3f& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156"
+        "bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293"
+        "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" -> "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156"
 }
diff --git a/doc/shape-shape-collision-call.dot b/doc/shape-shape-collision-call.dot
index 59e8467ed907ef5914bff4ec5f914c66fa4d73b0..58d666331f7053b7bf814e40b54d0a828d950d8c 100644
--- a/doc/shape-shape-collision-call.dot
+++ b/doc/shape-shape-collision-call.dot
@@ -4,16 +4,16 @@ digraph CD  {
 	compound=true
         size = 11.7
 
-        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
-        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" [shape = box]
+        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
+        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" [shape = box]
         "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" [shape = box]
         "void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" [shape = box]
         "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" [shape = box]
-        "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3f& tf1, const S2& s2, const Transform3f& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h" [shape = box]
+        "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h" [shape = box]
 
-        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" -> "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)"
-        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3f& tf1,\nconst CollisionGeometry* o2, const Transform3f& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" -> "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)"
+        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" -> "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)"
+        "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" -> "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)"
         "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" -> "void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)"
         "void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" -> "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h"
-        "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" -> "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3f& tf1, const S2& s2, const Transform3f& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h"
+        "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" -> "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h"
 }
diff --git a/include/coal/BV/BV.h b/include/coal/BV/BV.h
index aba2d1d493d49c62c6800a66ea48509a6428ad03..2224f791888c812ec220a9b637a61921da0bd9ca 100644
--- a/include/coal/BV/BV.h
+++ b/include/coal/BV/BV.h
@@ -56,14 +56,14 @@ namespace details {
 /// bounding volume of type BV2 in I configuration.
 template <typename BV1, typename BV2>
 struct Converter {
-  static void convert(const BV1& bv1, const Transform3f& tf1, BV2& bv2);
+  static void convert(const BV1& bv1, const Transform3s& tf1, BV2& bv2);
   static void convert(const BV1& bv1, BV2& bv2);
 };
 
 /// @brief Convert from AABB to AABB, not very tight but is fast.
 template <>
 struct Converter<AABB, AABB> {
-  static void convert(const AABB& bv1, const Transform3f& tf1, AABB& bv2) {
+  static void convert(const AABB& bv1, const Transform3s& tf1, AABB& bv2) {
     const Vec3s& center = bv1.center();
     CoalScalar r = (bv1.max_ - bv1.min_).norm() * 0.5;
     const Vec3s center2 = tf1.transform(center);
@@ -76,7 +76,7 @@ struct Converter<AABB, AABB> {
 
 template <>
 struct Converter<AABB, OBB> {
-  static void convert(const AABB& bv1, const Transform3f& tf1, OBB& bv2) {
+  static void convert(const AABB& bv1, const Transform3s& tf1, OBB& bv2) {
     bv2.To = tf1.transform(bv1.center());
     bv2.extent.noalias() = (bv1.max_ - bv1.min_) * 0.5;
     bv2.axes = tf1.getRotation();
@@ -91,7 +91,7 @@ struct Converter<AABB, OBB> {
 
 template <>
 struct Converter<OBB, OBB> {
-  static void convert(const OBB& bv1, const Transform3f& tf1, OBB& bv2) {
+  static void convert(const OBB& bv1, const Transform3s& tf1, OBB& bv2) {
     bv2.extent = bv1.extent;
     bv2.To = tf1.transform(bv1.To);
     bv2.axes.noalias() = tf1.getRotation() * bv1.axes;
@@ -102,7 +102,7 @@ struct Converter<OBB, OBB> {
 
 template <>
 struct Converter<OBBRSS, OBB> {
-  static void convert(const OBBRSS& bv1, const Transform3f& tf1, OBB& bv2) {
+  static void convert(const OBBRSS& bv1, const Transform3s& tf1, OBB& bv2) {
     Converter<OBB, OBB>::convert(bv1.obb, tf1, bv2);
   }
 
@@ -113,7 +113,7 @@ struct Converter<OBBRSS, OBB> {
 
 template <>
 struct Converter<RSS, OBB> {
-  static void convert(const RSS& bv1, const Transform3f& tf1, OBB& bv2) {
+  static void convert(const RSS& bv1, const Transform3s& tf1, OBB& bv2) {
     bv2.extent = Vec3s(bv1.length[0] * 0.5 + bv1.radius,
                        bv1.length[1] * 0.5 + bv1.radius, bv1.radius);
     bv2.To = tf1.transform(bv1.Tr);
@@ -130,7 +130,7 @@ struct Converter<RSS, OBB> {
 
 template <typename BV1>
 struct Converter<BV1, AABB> {
-  static void convert(const BV1& bv1, const Transform3f& tf1, AABB& bv2) {
+  static void convert(const BV1& bv1, const Transform3s& tf1, AABB& bv2) {
     const Vec3s& center = bv1.center();
     CoalScalar r = Vec3s(bv1.width(), bv1.height(), bv1.depth()).norm() * 0.5;
     const Vec3s center2 = tf1.transform(center);
@@ -148,7 +148,7 @@ struct Converter<BV1, AABB> {
 
 template <typename BV1>
 struct Converter<BV1, OBB> {
-  static void convert(const BV1& bv1, const Transform3f& tf1, OBB& bv2) {
+  static void convert(const BV1& bv1, const Transform3s& tf1, OBB& bv2) {
     AABB bv;
     Converter<BV1, AABB>::convert(bv1, bv);
     Converter<AABB, OBB>::convert(bv, tf1, bv2);
@@ -163,7 +163,7 @@ struct Converter<BV1, OBB> {
 
 template <>
 struct Converter<OBB, RSS> {
-  static void convert(const OBB& bv1, const Transform3f& tf1, RSS& bv2) {
+  static void convert(const OBB& bv1, const Transform3s& tf1, RSS& bv2) {
     bv2.Tr = tf1.transform(bv1.To);
     bv2.axes.noalias() = tf1.getRotation() * bv1.axes;
 
@@ -184,7 +184,7 @@ struct Converter<OBB, RSS> {
 
 template <>
 struct Converter<RSS, RSS> {
-  static void convert(const RSS& bv1, const Transform3f& tf1, RSS& bv2) {
+  static void convert(const RSS& bv1, const Transform3s& tf1, RSS& bv2) {
     bv2.Tr = tf1.transform(bv1.Tr);
     bv2.axes.noalias() = tf1.getRotation() * bv1.axes;
 
@@ -198,7 +198,7 @@ struct Converter<RSS, RSS> {
 
 template <>
 struct Converter<OBBRSS, RSS> {
-  static void convert(const OBBRSS& bv1, const Transform3f& tf1, RSS& bv2) {
+  static void convert(const OBBRSS& bv1, const Transform3s& tf1, RSS& bv2) {
     Converter<RSS, RSS>::convert(bv1.rss, tf1, bv2);
   }
 
@@ -209,7 +209,7 @@ struct Converter<OBBRSS, RSS> {
 
 template <>
 struct Converter<AABB, RSS> {
-  static void convert(const AABB& bv1, const Transform3f& tf1, RSS& bv2) {
+  static void convert(const AABB& bv1, const Transform3s& tf1, RSS& bv2) {
     bv2.Tr = tf1.transform(bv1.center());
 
     /// Sort the AABB edges so that AABB extents are ordered.
@@ -249,13 +249,13 @@ struct Converter<AABB, RSS> {
   }
 
   static void convert(const AABB& bv1, RSS& bv2) {
-    convert(bv1, Transform3f(), bv2);
+    convert(bv1, Transform3s(), bv2);
   }
 };
 
 template <>
 struct Converter<AABB, OBBRSS> {
-  static void convert(const AABB& bv1, const Transform3f& tf1, OBBRSS& bv2) {
+  static void convert(const AABB& bv1, const Transform3s& tf1, OBBRSS& bv2) {
     Converter<AABB, OBB>::convert(bv1, tf1, bv2.obb);
     Converter<AABB, RSS>::convert(bv1, tf1, bv2.rss);
   }
@@ -273,7 +273,7 @@ struct Converter<AABB, OBBRSS> {
 /// @brief Convert a bounding volume of type BV1 in configuration tf1 to
 /// bounding volume of type BV2 in identity configuration.
 template <typename BV1, typename BV2>
-static inline void convertBV(const BV1& bv1, const Transform3f& tf1, BV2& bv2) {
+static inline void convertBV(const BV1& bv1, const Transform3s& tf1, BV2& bv2) {
   details::Converter<BV1, BV2>::convert(bv1, tf1, bv2);
 }
 
diff --git a/include/coal/BVH/BVH_utility.h b/include/coal/BVH/BVH_utility.h
index ef24f8845f106f9d4eac2a3ab18d3a9065ae9760..daf0e478163da2351972cb1b129404467a2ba19b 100644
--- a/include/coal/BVH/BVH_utility.h
+++ b/include/coal/BVH/BVH_utility.h
@@ -45,39 +45,39 @@ namespace coal {
 /// A triangle in collision with the AABB is considered inside.
 template <typename BV>
 COAL_DLLAPI BVHModel<BV>* BVHExtract(const BVHModel<BV>& model,
-                                     const Transform3f& pose, const AABB& aabb);
+                                     const Transform3s& pose, const AABB& aabb);
 
 template <>
 COAL_DLLAPI BVHModel<OBB>* BVHExtract(const BVHModel<OBB>& model,
-                                      const Transform3f& pose,
+                                      const Transform3s& pose,
                                       const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<AABB>* BVHExtract(const BVHModel<AABB>& model,
-                                       const Transform3f& pose,
+                                       const Transform3s& pose,
                                        const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<RSS>* BVHExtract(const BVHModel<RSS>& model,
-                                      const Transform3f& pose,
+                                      const Transform3s& pose,
                                       const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<kIOS>* BVHExtract(const BVHModel<kIOS>& model,
-                                       const Transform3f& pose,
+                                       const Transform3s& pose,
                                        const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<OBBRSS>* BVHExtract(const BVHModel<OBBRSS>& model,
-                                         const Transform3f& pose,
+                                         const Transform3s& pose,
                                          const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<KDOP<16> >* BVHExtract(const BVHModel<KDOP<16> >& model,
-                                            const Transform3f& pose,
+                                            const Transform3s& pose,
                                             const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<KDOP<18> >* BVHExtract(const BVHModel<KDOP<18> >& model,
-                                            const Transform3f& pose,
+                                            const Transform3s& pose,
                                             const AABB& aabb);
 template <>
 COAL_DLLAPI BVHModel<KDOP<24> >* BVHExtract(const BVHModel<KDOP<24> >& model,
-                                            const Transform3f& pose,
+                                            const Transform3s& pose,
                                             const AABB& aabb);
 
 /// @brief Compute the covariance matrix for a set or subset of points. if ts =
diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h
index 870e39b067d2dd8c2231cd1fb11b3110f05459f5..6e1314f6e88fc725ede812f3a4de3a126ee825e1 100644
--- a/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h
+++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h
@@ -71,8 +71,8 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
         const AABB& root2_bv_t = translate(root2_bv, translation2);
         if (root1->bv.overlap(root2_bv_t)) {
           Box* box = new Box();
-          Transform3f box_tf;
-          Transform3f tf2 = Transform3f::Identity();
+          Transform3s box_tf;
+          Transform3s tf2 = Transform3s::Identity();
           tf2.translation() = translation2;
           constructBox(root2_bv, tf2, *box, box_tf);
 
@@ -100,8 +100,8 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
       const AABB& root2_bv_t = translate(root2_bv, translation2);
       if (root1->bv.overlap(root2_bv_t)) {
         Box* box = new Box();
-        Transform3f box_tf;
-        Transform3f tf2 = Transform3f::Identity();
+        Transform3s box_tf;
+        Transform3s tf2 = Transform3s::Identity();
         tf2.translation() = translation2;
         constructBox(root2_bv, tf2, *box, box_tf);
 
@@ -159,8 +159,8 @@ bool distanceRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
   if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
     if (tree2->isNodeOccupied(root2)) {
       Box* box = new Box();
-      Transform3f box_tf;
-      Transform3f tf2 = Transform3f::Identity();
+      Transform3s box_tf;
+      Transform3s tf2 = Transform3s::Identity();
       tf2.translation() = translation2;
       constructBox(root2_bv, tf2, *box, box_tf);
       CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
index 2965551665507828b39c315c09b9084ffab32425..730db5782ffc0d1a49aff397e64c59b3afcca145 100644
--- a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
+++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
@@ -68,8 +68,8 @@ bool collisionRecurse_(
         const AABB& root_bv_t = translate(root2_bv, translation2);
         if (root1->bv.overlap(root_bv_t)) {
           Box* box = new Box();
-          Transform3f box_tf;
-          Transform3f tf2 = Transform3f::Identity();
+          Transform3s box_tf;
+          Transform3s tf2 = Transform3s::Identity();
           tf2.translation() = translation2;
           constructBox(root2_bv, tf2, *box, box_tf);
 
@@ -95,8 +95,8 @@ bool collisionRecurse_(
       const AABB& root_bv_t = translate(root2_bv, translation2);
       if (root1->bv.overlap(root_bv_t)) {
         Box* box = new Box();
-        Transform3f box_tf;
-        Transform3f tf2 = Transform3f::Identity();
+        Transform3s box_tf;
+        Transform3s tf2 = Transform3s::Identity();
         tf2.translation() = translation2;
         constructBox(root2_bv, tf2, *box, box_tf);
 
@@ -157,8 +157,8 @@ bool distanceRecurse_(
   if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
     if (tree2->isNodeOccupied(root2)) {
       Box* box = new Box();
-      Transform3f box_tf;
-      Transform3f tf2 = Transform3f::Identity();
+      Transform3s box_tf;
+      Transform3s tf2 = Transform3s::Identity();
       tf2.translation() = translation2;
       constructBox(root2_bv, tf2, *box, box_tf);
       CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
diff --git a/include/coal/collision.h b/include/coal/collision.h
index 39ae20b63954a3522a16107ca765a572f157774d..cf9b9a1c01e55825fd769e5f920e05b59fbec83d 100644
--- a/include/coal/collision.h
+++ b/include/coal/collision.h
@@ -62,9 +62,9 @@ COAL_DLLAPI std::size_t collide(const CollisionObject* o1,
 /// @copydoc collide(const CollisionObject*, const CollisionObject*, const
 /// CollisionRequest&, CollisionResult&)
 COAL_DLLAPI std::size_t collide(const CollisionGeometry* o1,
-                                const Transform3f& tf1,
+                                const Transform3s& tf1,
                                 const CollisionGeometry* o2,
-                                const Transform3f& tf2,
+                                const Transform3s& tf2,
                                 const CollisionRequest& request,
                                 CollisionResult& result);
 
@@ -80,7 +80,7 @@ class COAL_DLLAPI ComputeCollision {
   /// @brief Default constructor from two Collision Geometries.
   ComputeCollision(const CollisionGeometry* o1, const CollisionGeometry* o2);
 
-  std::size_t operator()(const Transform3f& tf1, const Transform3f& tf2,
+  std::size_t operator()(const Transform3s& tf1, const Transform3s& tf2,
                          const CollisionRequest& request,
                          CollisionResult& result) const;
 
@@ -107,7 +107,7 @@ class COAL_DLLAPI ComputeCollision {
   CollisionFunctionMatrix::CollisionFunc func;
   bool swap_geoms;
 
-  virtual std::size_t run(const Transform3f& tf1, const Transform3f& tf2,
+  virtual std::size_t run(const Transform3s& tf1, const Transform3s& tf2,
                           const CollisionRequest& request,
                           CollisionResult& result) const;
 
diff --git a/include/coal/collision_data.h b/include/coal/collision_data.h
index 7be9827ac412bc2d644976d113c4be8145f127b8..6e17f0485a45ac0470d281180304fbbf517b8927 100644
--- a/include/coal/collision_data.h
+++ b/include/coal/collision_data.h
@@ -515,7 +515,7 @@ struct COAL_DLLAPI ContactPatch {
 
   /// @brief Frame of the set, expressed in the world coordinates.
   /// The z-axis of the frame's rotation is the contact patch normal.
-  Transform3f tf;
+  Transform3s tf;
 
   /// @brief Direction of ContactPatch.
   /// When doing collision detection, the convention of Coal is that the
@@ -559,7 +559,7 @@ struct COAL_DLLAPI ContactPatch {
   /// of the patch is known in advance. Coal will automatically expand/shrink
   /// the contact patch if needed.
   explicit ContactPatch(size_t preallocated_size = default_preallocated_size)
-      : tf(Transform3f::Identity()),
+      : tf(Transform3s::Identity()),
         direction(PatchDirection::DEFAULT),
         penetration_depth(0) {
     this->m_points.reserve(preallocated_size);
diff --git a/include/coal/collision_func_matrix.h b/include/coal/collision_func_matrix.h
index 4311d46136eec8b59f65c5359b09ec4afdf03cee..e9aeca48f6a4c6a2c33e14074487ee9961afe616 100644
--- a/include/coal/collision_func_matrix.h
+++ b/include/coal/collision_func_matrix.h
@@ -58,9 +58,9 @@ struct COAL_DLLAPI CollisionFunctionMatrix {
   /// information, whether need to compute cost);
   /// 4. the structure to return collision result
   typedef std::size_t (*CollisionFunc)(const CollisionGeometry* o1,
-                                       const Transform3f& tf1,
+                                       const Transform3s& tf1,
                                        const CollisionGeometry* o2,
-                                       const Transform3f& tf2,
+                                       const Transform3s& tf2,
                                        const GJKSolver* nsolver,
                                        const CollisionRequest& request,
                                        CollisionResult& result);
diff --git a/include/coal/collision_object.h b/include/coal/collision_object.h
index 503ca6016210055dcf55748d8f706b16adb8c109..ccc5cf13618a388c97431eab41fa62c176164543 100644
--- a/include/coal/collision_object.h
+++ b/include/coal/collision_object.h
@@ -220,7 +220,7 @@ class COAL_DLLAPI CollisionObject {
   }
 
   CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
-                  const Transform3f& tf, bool compute_local_aabb = true)
+                  const Transform3s& tf, bool compute_local_aabb = true)
       : cgeom(cgeom_), t(tf), user_data(nullptr) {
     init(compute_local_aabb);
   }
@@ -287,7 +287,7 @@ class COAL_DLLAPI CollisionObject {
   inline const Matrix3s& getRotation() const { return t.getRotation(); }
 
   /// @brief get object's transform
-  inline const Transform3f& getTransform() const { return t; }
+  inline const Transform3s& getTransform() const { return t; }
 
   /// @brief set object's rotation matrix
   void setRotation(const Matrix3s& R) { t.setRotation(R); }
@@ -299,7 +299,7 @@ class COAL_DLLAPI CollisionObject {
   void setTransform(const Matrix3s& R, const Vec3s& T) { t.setTransform(R, T); }
 
   /// @brief set object's transform
-  void setTransform(const Transform3f& tf) { t = tf; }
+  void setTransform(const Transform3s& tf) { t = tf; }
 
   /// @brief whether the object is in local coordinate
   bool isIdentityTransform() const { return t.isIdentity(); }
@@ -346,7 +346,7 @@ class COAL_DLLAPI CollisionObject {
 
   shared_ptr<CollisionGeometry> cgeom;
 
-  Transform3f t;
+  Transform3s t;
 
   /// @brief AABB in global coordinate
   mutable AABB aabb;
diff --git a/include/coal/collision_utility.h b/include/coal/collision_utility.h
index 19aa534a8d467ac4c0ea66fe805774ad3d7ef605..44a597d2693bb462eb2001c22f35baa03f103d56 100644
--- a/include/coal/collision_utility.h
+++ b/include/coal/collision_utility.h
@@ -23,7 +23,7 @@
 namespace coal {
 
 COAL_DLLAPI CollisionGeometry* extract(const CollisionGeometry* model,
-                                       const Transform3f& pose,
+                                       const Transform3s& pose,
                                        const AABB& aabb);
 
 /**
diff --git a/include/coal/contact_patch.h b/include/coal/contact_patch.h
index edea02d2cbfa534cd12e43ea5b358103ac3e0236..a942fa0b9f5d8b75c0cde0f7a141777fc6df2512 100644
--- a/include/coal/contact_patch.h
+++ b/include/coal/contact_patch.h
@@ -50,15 +50,15 @@ namespace coal {
 /// read @ref ContactPatch if you want to fully understand what is meant by
 /// "contact patch".
 COAL_DLLAPI void computeContactPatch(const CollisionGeometry* o1,
-                                     const Transform3f& tf1,
+                                     const Transform3s& tf1,
                                      const CollisionGeometry* o2,
-                                     const Transform3f& tf2,
+                                     const Transform3s& tf2,
                                      const CollisionResult& collision_result,
                                      const ContactPatchRequest& request,
                                      ContactPatchResult& result);
 
-/// @copydoc computeContactPatch(const CollisionGeometry*, const Transform3f&,
-// const CollisionGeometry*, const Transform3f&, const CollisionResult&, const
+/// @copydoc computeContactPatch(const CollisionGeometry*, const Transform3s&,
+// const CollisionGeometry*, const Transform3s&, const CollisionResult&, const
 // ContactPatchRequest&, ContactPatchResult&);
 COAL_DLLAPI void computeContactPatch(const CollisionObject* o1,
                                      const CollisionObject* o2,
@@ -79,7 +79,7 @@ class COAL_DLLAPI ComputeContactPatch {
   /// @brief Default constructor from two Collision Geometries.
   ComputeContactPatch(const CollisionGeometry* o1, const CollisionGeometry* o2);
 
-  void operator()(const Transform3f& tf1, const Transform3f& tf2,
+  void operator()(const Transform3s& tf1, const Transform3s& tf2,
                   const CollisionResult& collision_result,
                   const ContactPatchRequest& request,
                   ContactPatchResult& result) const;
@@ -108,7 +108,7 @@ class COAL_DLLAPI ComputeContactPatch {
   ContactPatchFunctionMatrix::ContactPatchFunc func;
   bool swap_geoms;
 
-  virtual void run(const Transform3f& tf1, const Transform3f& tf2,
+  virtual void run(const Transform3s& tf1, const Transform3s& tf2,
                    const CollisionResult& collision_result,
                    const ContactPatchRequest& request,
                    ContactPatchResult& result) const;
diff --git a/include/coal/contact_patch/contact_patch_solver.h b/include/coal/contact_patch/contact_patch_solver.h
index 63c7fd3420e70b45245da98a16317699b3fbc583..cce436ea107f93fd9fb9411451ef2f05c618f4be 100644
--- a/include/coal/contact_patch/contact_patch_solver.h
+++ b/include/coal/contact_patch/contact_patch_solver.h
@@ -160,14 +160,14 @@ struct COAL_DLLAPI ContactPatchSolver {
   /// plane passing (by `contact.pos` and supported by `contact.normal`) and the
   /// shapes s1 and s2.
   template <typename ShapeType1, typename ShapeType2>
-  void computePatch(const ShapeType1& s1, const Transform3f& tf1,
-                    const ShapeType2& s2, const Transform3f& tf2,
+  void computePatch(const ShapeType1& s1, const Transform3s& tf1,
+                    const ShapeType2& s2, const Transform3s& tf2,
                     const Contact& contact, ContactPatch& contact_patch) const;
 
   /// @brief Reset the internal quantities of the solver.
   template <typename ShapeType1, typename ShapeType2>
-  void reset(const ShapeType1& shape1, const Transform3f& tf1,
-             const ShapeType2& shape2, const Transform3f& tf2,
+  void reset(const ShapeType1& shape1, const Transform3s& tf1,
+             const ShapeType2& shape2, const Transform3s& tf2,
              const ContactPatch& contact_patch) const;
 
   /// @brief Retrieve result, adds a post-processing step if result has bigger
diff --git a/include/coal/contact_patch/contact_patch_solver.hxx b/include/coal/contact_patch/contact_patch_solver.hxx
index 403612f37e3b4f15f3963cb662a9f5a14ad5e9b9..f4f97b02cfb6eacf3196e272dc3e8310da65dfb1 100644
--- a/include/coal/contact_patch/contact_patch_solver.hxx
+++ b/include/coal/contact_patch/contact_patch_solver.hxx
@@ -74,9 +74,9 @@ inline void ContactPatchSolver::set(const ContactPatchRequest& request) {
 // ============================================================================
 template <typename ShapeType1, typename ShapeType2>
 void ContactPatchSolver::computePatch(const ShapeType1& s1,
-                                      const Transform3f& tf1,
+                                      const Transform3s& tf1,
                                       const ShapeType2& s2,
-                                      const Transform3f& tf2,
+                                      const Transform3s& tf2,
                                       const Contact& contact,
                                       ContactPatch& contact_patch) const {
   // Note: `ContactPatch` is an alias for `SupportSet`.
@@ -372,9 +372,9 @@ inline void ContactPatchSolver::getResult(
 // ============================================================================
 template <typename ShapeType1, typename ShapeType2>
 inline void ContactPatchSolver::reset(const ShapeType1& shape1,
-                                      const Transform3f& tf1,
+                                      const Transform3s& tf1,
                                       const ShapeType2& shape2,
-                                      const Transform3f& tf2,
+                                      const Transform3s& tf2,
                                       const ContactPatch& contact_patch) const {
   // Reset internal quantities
   this->support_set_shape1.clear();
@@ -382,12 +382,12 @@ inline void ContactPatchSolver::reset(const ShapeType1& shape1,
   this->support_set_buffer.clear();
 
   // Get the support function of each shape
-  const Transform3f& tfc = contact_patch.tf;
+  const Transform3s& tfc = contact_patch.tf;
 
   this->support_set_shape1.direction = SupportSetDirection::DEFAULT;
   // Set the reference frame of the support set of the first shape to be the
   // local frame of shape 1.
-  Transform3f& tf1c = this->support_set_shape1.tf;
+  Transform3s& tf1c = this->support_set_shape1.tf;
   tf1c.rotation().noalias() = tf1.rotation().transpose() * tfc.rotation();
   tf1c.translation().noalias() =
       tf1.rotation().transpose() * (tfc.translation() - tf1.translation());
@@ -397,7 +397,7 @@ inline void ContactPatchSolver::reset(const ShapeType1& shape1,
   this->support_set_shape2.direction = SupportSetDirection::INVERTED;
   // Set the reference frame of the support set of the second shape to be the
   // local frame of shape 2.
-  Transform3f& tf2c = this->support_set_shape2.tf;
+  Transform3s& tf2c = this->support_set_shape2.tf;
   tf2c.rotation().noalias() = tf2.rotation().transpose() * tfc.rotation();
   tf2c.translation().noalias() =
       tf2.rotation().transpose() * (tfc.translation() - tf2.translation());
diff --git a/include/coal/contact_patch_func_matrix.h b/include/coal/contact_patch_func_matrix.h
index ec2aeb49682758f9eee8912f91bf6965a0fef5df..f95d73c4eb6341ab7be3cffe2608c1cdc708a032 100644
--- a/include/coal/contact_patch_func_matrix.h
+++ b/include/coal/contact_patch_func_matrix.h
@@ -65,9 +65,9 @@ struct COAL_DLLAPI ContactPatchFunctionMatrix {
   /// tf1 and tf2 and make multiple calls to the GJKSolver (although this is not
   /// the approach done by default).
   typedef void (*ContactPatchFunc)(const CollisionGeometry* o1,
-                                   const Transform3f& tf1,
+                                   const Transform3s& tf1,
                                    const CollisionGeometry* o2,
-                                   const Transform3f& tf2,
+                                   const Transform3s& tf2,
                                    const CollisionResult& collision_result,
                                    const ContactPatchSolver* csolver,
                                    const ContactPatchRequest& request,
diff --git a/include/coal/distance.h b/include/coal/distance.h
index 21da64876582b5c108fef8ce3a95a06938a2c708..7dd4a3e7d544a23f96332d84051a095a258f1d35 100644
--- a/include/coal/distance.h
+++ b/include/coal/distance.h
@@ -57,9 +57,9 @@ COAL_DLLAPI CoalScalar distance(const CollisionObject* o1,
 /// @copydoc distance(const CollisionObject*, const CollisionObject*, const
 /// DistanceRequest&, DistanceResult&)
 COAL_DLLAPI CoalScalar distance(const CollisionGeometry* o1,
-                                const Transform3f& tf1,
+                                const Transform3s& tf1,
                                 const CollisionGeometry* o2,
-                                const Transform3f& tf2,
+                                const Transform3s& tf2,
                                 const DistanceRequest& request,
                                 DistanceResult& result);
 
@@ -74,7 +74,7 @@ class COAL_DLLAPI ComputeDistance {
  public:
   ComputeDistance(const CollisionGeometry* o1, const CollisionGeometry* o2);
 
-  CoalScalar operator()(const Transform3f& tf1, const Transform3f& tf2,
+  CoalScalar operator()(const Transform3s& tf1, const Transform3s& tf2,
                         const DistanceRequest& request,
                         DistanceResult& result) const;
 
@@ -102,7 +102,7 @@ class COAL_DLLAPI ComputeDistance {
   DistanceFunctionMatrix::DistanceFunc func;
   bool swap_geoms;
 
-  virtual CoalScalar run(const Transform3f& tf1, const Transform3f& tf2,
+  virtual CoalScalar run(const Transform3s& tf1, const Transform3s& tf2,
                          const DistanceRequest& request,
                          DistanceResult& result) const;
 
diff --git a/include/coal/distance_func_matrix.h b/include/coal/distance_func_matrix.h
index febcc663d37395d40916776717bf53c2ca4fb755..a37e1df51cba80f5be2f1ada872a8af8e6c574d6 100644
--- a/include/coal/distance_func_matrix.h
+++ b/include/coal/distance_func_matrix.h
@@ -55,9 +55,9 @@ struct COAL_DLLAPI DistanceFunctionMatrix {
   /// 3. the request setting for distance (e.g., whether need to return nearest
   /// points);
   typedef CoalScalar (*DistanceFunc)(const CollisionGeometry* o1,
-                                     const Transform3f& tf1,
+                                     const Transform3s& tf1,
                                      const CollisionGeometry* o2,
-                                     const Transform3f& tf2,
+                                     const Transform3s& tf2,
                                      const GJKSolver* nsolver,
                                      const DistanceRequest& request,
                                      DistanceResult& result);
diff --git a/include/coal/fwd.hh b/include/coal/fwd.hh
index 196a207cfec145266a774cf2bafb0fac4b1b9fcf..8be5e49a8c32473c9ff82861fdd33b9b433ab16a 100644
--- a/include/coal/fwd.hh
+++ b/include/coal/fwd.hh
@@ -134,7 +134,7 @@ typedef shared_ptr<const CollisionObject> CollisionObjectConstPtr_t;
 class CollisionGeometry;
 typedef shared_ptr<CollisionGeometry> CollisionGeometryPtr_t;
 typedef shared_ptr<const CollisionGeometry> CollisionGeometryConstPtr_t;
-class Transform3f;
+class Transform3s;
 
 class AABB;
 
diff --git a/include/coal/internal/intersect.h b/include/coal/internal/intersect.h
index 4b5ef8d70af16f07ad771c2185503f26738cd6e2..350101cffea84175220d2bf705539549c559de7c 100644
--- a/include/coal/internal/intersect.h
+++ b/include/coal/internal/intersect.h
@@ -146,7 +146,7 @@ class COAL_DLLAPI TriangleDistance {
   /// from the triangles, not coincident points on the intersection of the
   /// triangles, as might be expected.
   static CoalScalar sqrTriDistance(const Vec3s S[3], const Vec3s T[3],
-                                   const Transform3f& tf, Vec3s& P, Vec3s& Q);
+                                   const Transform3s& tf, Vec3s& P, Vec3s& Q);
 
   /// Compute squared distance between triangles
   /// @param S1, S2, S3 and T1, T2, T3 are triangle vertices
@@ -177,7 +177,7 @@ class COAL_DLLAPI TriangleDistance {
   static CoalScalar sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
                                    const Vec3s& S3, const Vec3s& T1,
                                    const Vec3s& T2, const Vec3s& T3,
-                                   const Transform3f& tf, Vec3s& P, Vec3s& Q);
+                                   const Transform3s& tf, Vec3s& P, Vec3s& Q);
 };
 
 }  // namespace coal
diff --git a/include/coal/internal/shape_shape_contact_patch_func.h b/include/coal/internal/shape_shape_contact_patch_func.h
index b18b6bbc3a470b3cf9523139704591d9caf97114..3eb28b539fda0246da672c4231a4bb122960cee2 100644
--- a/include/coal/internal/shape_shape_contact_patch_func.h
+++ b/include/coal/internal/shape_shape_contact_patch_func.h
@@ -50,8 +50,8 @@ namespace coal {
 /// by the `ContactPatchRequest`.
 template <typename ShapeType1, typename ShapeType2>
 struct ComputeShapeShapeContactPatch {
-  static void run(const CollisionGeometry* o1, const Transform3f& tf1,
-                  const CollisionGeometry* o2, const Transform3f& tf2,
+  static void run(const CollisionGeometry* o1, const Transform3s& tf1,
+                  const CollisionGeometry* o2, const Transform3s& tf2,
                   const CollisionResult& collision_result,
                   const ContactPatchSolver* csolver,
                   const ContactPatchRequest& request,
@@ -88,9 +88,9 @@ struct ComputeShapeShapeContactPatch {
 /// this function).
 template <bool InvertShapes, typename OtherShapeType, typename PlaneOrHalfspace>
 void computePatchPlaneOrHalfspace(const OtherShapeType& s1,
-                                  const Transform3f& tf1,
+                                  const Transform3s& tf1,
                                   const PlaneOrHalfspace& s2,
-                                  const Transform3f& tf2,
+                                  const Transform3s& tf2,
                                   const ContactPatchSolver* csolver,
                                   const Contact& contact,
                                   ContactPatch& contact_patch) {
@@ -134,8 +134,8 @@ void computePatchPlaneOrHalfspace(const OtherShapeType& s1,
 #define PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH(PlaneOrHspace)          \
   template <typename OtherShapeType>                                          \
   struct ComputeShapeShapeContactPatch<OtherShapeType, PlaneOrHspace> {       \
-    static void run(const CollisionGeometry* o1, const Transform3f& tf1,      \
-                    const CollisionGeometry* o2, const Transform3f& tf2,      \
+    static void run(const CollisionGeometry* o1, const Transform3s& tf1,      \
+                    const CollisionGeometry* o2, const Transform3s& tf2,      \
                     const CollisionResult& collision_result,                  \
                     const ContactPatchSolver* csolver,                        \
                     const ContactPatchRequest& request,                       \
@@ -168,8 +168,8 @@ void computePatchPlaneOrHalfspace(const OtherShapeType& s1,
                                                                               \
   template <typename OtherShapeType>                                          \
   struct ComputeShapeShapeContactPatch<PlaneOrHspace, OtherShapeType> {       \
-    static void run(const CollisionGeometry* o1, const Transform3f& tf1,      \
-                    const CollisionGeometry* o2, const Transform3f& tf2,      \
+    static void run(const CollisionGeometry* o1, const Transform3s& tf1,      \
+                    const CollisionGeometry* o2, const Transform3s& tf2,      \
                     const CollisionResult& collision_result,                  \
                     const ContactPatchSolver* csolver,                        \
                     const ContactPatchRequest& request,                       \
@@ -206,8 +206,8 @@ PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH(Halfspace)
 #define PLANE_HSPACE_CONTACT_PATCH(PlaneOrHspace1, PlaneOrHspace2)           \
   template <>                                                                \
   struct ComputeShapeShapeContactPatch<PlaneOrHspace1, PlaneOrHspace2> {     \
-    static void run(const CollisionGeometry* o1, const Transform3f& tf1,     \
-                    const CollisionGeometry* o2, const Transform3f& tf2,     \
+    static void run(const CollisionGeometry* o1, const Transform3s& tf1,     \
+                    const CollisionGeometry* o2, const Transform3s& tf2,     \
                     const CollisionResult& collision_result,                 \
                     const ContactPatchSolver* csolver,                       \
                     const ContactPatchRequest& request,                      \
@@ -249,8 +249,8 @@ PLANE_HSPACE_CONTACT_PATCH(Halfspace, Halfspace)
 #undef PLANE_HSPACE_CONTACT_PATCH
 
 template <typename ShapeType1, typename ShapeType2>
-void ShapeShapeContactPatch(const CollisionGeometry* o1, const Transform3f& tf1,
-                            const CollisionGeometry* o2, const Transform3f& tf2,
+void ShapeShapeContactPatch(const CollisionGeometry* o1, const Transform3s& tf1,
+                            const CollisionGeometry* o2, const Transform3s& tf2,
                             const CollisionResult& collision_result,
                             const ContactPatchSolver* csolver,
                             const ContactPatchRequest& request,
diff --git a/include/coal/internal/shape_shape_func.h b/include/coal/internal/shape_shape_func.h
index 1d518e7f0c80f93aa50e907ed91645036f161c94..eb18b3ae9be03910a53286519e90b0abb7a289b7 100644
--- a/include/coal/internal/shape_shape_func.h
+++ b/include/coal/internal/shape_shape_func.h
@@ -49,8 +49,8 @@ namespace coal {
 
 template <typename ShapeType1, typename ShapeType2>
 struct ShapeShapeDistancer {
-  static CoalScalar run(const CollisionGeometry* o1, const Transform3f& tf1,
-                        const CollisionGeometry* o2, const Transform3f& tf2,
+  static CoalScalar run(const CollisionGeometry* o1, const Transform3s& tf1,
+                        const CollisionGeometry* o2, const Transform3s& tf2,
                         const GJKSolver* nsolver,
                         const DistanceRequest& request,
                         DistanceResult& result) {
@@ -70,8 +70,8 @@ struct ShapeShapeDistancer {
     return distance;
   }
 
-  static CoalScalar run(const CollisionGeometry* o1, const Transform3f& tf1,
-                        const CollisionGeometry* o2, const Transform3f& tf2,
+  static CoalScalar run(const CollisionGeometry* o1, const Transform3s& tf1,
+                        const CollisionGeometry* o2, const Transform3s& tf2,
                         const GJKSolver* nsolver,
                         const bool compute_signed_distance, Vec3s& p1,
                         Vec3s& p2, Vec3s& normal) {
@@ -91,9 +91,9 @@ struct ShapeShapeDistancer {
 /// @note This function might be specialized for some pairs of shapes.
 template <typename ShapeType1, typename ShapeType2>
 CoalScalar ShapeShapeDistance(const CollisionGeometry* o1,
-                              const Transform3f& tf1,
+                              const Transform3s& tf1,
                               const CollisionGeometry* o2,
-                              const Transform3f& tf2, const GJKSolver* nsolver,
+                              const Transform3s& tf2, const GJKSolver* nsolver,
                               const DistanceRequest& request,
                               DistanceResult& result) {
   return ShapeShapeDistancer<ShapeType1, ShapeType2>::run(
@@ -113,9 +113,9 @@ namespace internal {
 /// @note This function might be specialized for some pairs of shapes.
 template <typename ShapeType1, typename ShapeType2>
 CoalScalar ShapeShapeDistance(const CollisionGeometry* o1,
-                              const Transform3f& tf1,
+                              const Transform3s& tf1,
                               const CollisionGeometry* o2,
-                              const Transform3f& tf2, const GJKSolver* nsolver,
+                              const Transform3s& tf2, const GJKSolver* nsolver,
                               const bool compute_signed_distance, Vec3s& p1,
                               Vec3s& p2, Vec3s& normal) {
   return ::coal::ShapeShapeDistancer<ShapeType1, ShapeType2>::run(
@@ -134,8 +134,8 @@ CoalScalar ShapeShapeDistance(const CollisionGeometry* o1,
 /// internal collision detection checks.
 template <typename ShapeType1, typename ShapeType2>
 struct ShapeShapeCollider {
-  static std::size_t run(const CollisionGeometry* o1, const Transform3f& tf1,
-                         const CollisionGeometry* o2, const Transform3f& tf2,
+  static std::size_t run(const CollisionGeometry* o1, const Transform3s& tf1,
+                         const CollisionGeometry* o2, const Transform3s& tf2,
                          const GJKSolver* nsolver,
                          const CollisionRequest& request,
                          CollisionResult& result) {
@@ -168,9 +168,9 @@ struct ShapeShapeCollider {
 
 template <typename ShapeType1, typename ShapeType2>
 std::size_t ShapeShapeCollide(const CollisionGeometry* o1,
-                              const Transform3f& tf1,
+                              const Transform3s& tf1,
                               const CollisionGeometry* o2,
-                              const Transform3f& tf2, const GJKSolver* nsolver,
+                              const Transform3s& tf2, const GJKSolver* nsolver,
                               const CollisionRequest& request,
                               CollisionResult& result) {
   return ShapeShapeCollider<ShapeType1, ShapeType2>::run(
@@ -217,20 +217,20 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1,
 #define SHAPE_SHAPE_DISTANCE_SPECIALIZATION(T1, T2)                            \
   template <>                                                                  \
   COAL_DLLAPI CoalScalar internal::ShapeShapeDistance<T1, T2>(                 \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const bool compute_signed_distance, Vec3s& p1, \
       Vec3s& p2, Vec3s& normal);                                               \
   template <>                                                                  \
   COAL_DLLAPI CoalScalar internal::ShapeShapeDistance<T2, T1>(                 \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const bool compute_signed_distance, Vec3s& p1, \
       Vec3s& p2, Vec3s& normal);                                               \
   template <>                                                                  \
   inline COAL_DLLAPI CoalScalar ShapeShapeDistance<T1, T2>(                    \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const DistanceRequest& request,                \
       DistanceResult& result) {                                                \
     result.o1 = o1;                                                            \
@@ -244,8 +244,8 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1,
   }                                                                            \
   template <>                                                                  \
   inline COAL_DLLAPI CoalScalar ShapeShapeDistance<T2, T1>(                    \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const DistanceRequest& request,                \
       DistanceResult& result) {                                                \
     result.o1 = o1;                                                            \
@@ -261,14 +261,14 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1,
 #define SHAPE_SELF_DISTANCE_SPECIALIZATION(T)                                  \
   template <>                                                                  \
   COAL_DLLAPI CoalScalar internal::ShapeShapeDistance<T, T>(                   \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const bool compute_signed_distance, Vec3s& p1, \
       Vec3s& p2, Vec3s& normal);                                               \
   template <>                                                                  \
   inline COAL_DLLAPI CoalScalar ShapeShapeDistance<T, T>(                      \
-      const CollisionGeometry* o1, const Transform3f& tf1,                     \
-      const CollisionGeometry* o2, const Transform3f& tf2,                     \
+      const CollisionGeometry* o1, const Transform3s& tf1,                     \
+      const CollisionGeometry* o2, const Transform3s& tf2,                     \
       const GJKSolver* nsolver, const DistanceRequest& request,                \
       DistanceResult& result) {                                                \
     result.o1 = o1;                                                            \
diff --git a/include/coal/internal/traversal_node_base.h b/include/coal/internal/traversal_node_base.h
index 238dfc1a37b08898f163cb351d55f832f3ae8720..edd252985a75c988655c74a061495acb1a8947b7 100644
--- a/include/coal/internal/traversal_node_base.h
+++ b/include/coal/internal/traversal_node_base.h
@@ -85,10 +85,10 @@ class TraversalNodeBase {
   void enableStatistics(bool enable) { enable_statistics = enable; }
 
   /// @brief configuation of first object
-  Transform3f tf1;
+  Transform3s tf1;
 
   /// @brief configuration of second object
-  Transform3f tf2;
+  Transform3s tf2;
 
   /// @brief Whether stores statistics
   bool enable_statistics;
diff --git a/include/coal/internal/traversal_node_bvh_shape.h b/include/coal/internal/traversal_node_bvh_shape.h
index cff2a801b396b1cf4acab2af5b9b447da1fd1406..5b85879a550703d8302d266efa78145507843f8c 100644
--- a/include/coal/internal/traversal_node_bvh_shape.h
+++ b/include/coal/internal/traversal_node_bvh_shape.h
@@ -157,7 +157,7 @@ class MeshShapeCollisionTraversalNode
     CoalScalar distance;
 
     if (RTIsIdentity) {
-      static const Transform3f Id;
+      static const Transform3s Id;
       distance = internal::ShapeShapeDistance<TriangleP, S>(
           &tri, Id, this->model2, this->tf2, this->nsolver, compute_penetration,
           c1, c2, normal);
@@ -341,7 +341,7 @@ template <typename BV, typename S>
 void meshShapeDistanceOrientedNodeleafComputeDistance(
     unsigned int b1, unsigned int /* b2 */, const BVHModel<BV>* model1,
     const S& model2, Vec3s* vertices, Triangle* tri_indices,
-    const Transform3f& tf1, const Transform3f& tf2, const GJKSolver* nsolver,
+    const Transform3s& tf1, const Transform3s& tf2, const GJKSolver* nsolver,
     bool enable_statistics, int& num_leaf_tests, const DistanceRequest& request,
     DistanceResult& result) {
   if (enable_statistics) num_leaf_tests++;
@@ -365,8 +365,8 @@ void meshShapeDistanceOrientedNodeleafComputeDistance(
 template <typename BV, typename S>
 static inline void distancePreprocessOrientedNode(
     const BVHModel<BV>* model1, Vec3s* vertices, Triangle* tri_indices,
-    int init_tri_id, const S& model2, const Transform3f& tf1,
-    const Transform3f& tf2, const GJKSolver* nsolver,
+    int init_tri_id, const S& model2, const Transform3s& tf1,
+    const Transform3s& tf2, const GJKSolver* nsolver,
     const DistanceRequest& request, DistanceResult& result) {
   const Triangle& tri_id = tri_indices[init_tri_id];
   const TriangleP tri(vertices[tri_id[0]], vertices[tri_id[1]],
diff --git a/include/coal/internal/traversal_node_hfield_shape.h b/include/coal/internal/traversal_node_hfield_shape.h
index 438f5c8ccb173c26669ca3c5a3823f94aec1fff4..20e6202c26959c60677d3822cd8c5ac413af6766 100644
--- a/include/coal/internal/traversal_node_hfield_shape.h
+++ b/include/coal/internal/traversal_node_hfield_shape.h
@@ -320,7 +320,7 @@ inline CoalScalar distanceContactPointToFace(const size_t face_id,
 template <typename Polygone, typename Shape>
 bool binCorrection(const Convex<Polygone>& convex,
                    const int convex_active_faces, const Shape& shape,
-                   const Transform3f& shape_pose, CoalScalar& distance,
+                   const Transform3s& shape_pose, CoalScalar& distance,
                    Vec3s& contact_1, Vec3s& contact_2, Vec3s& normal,
                    Vec3s& face_normal, const bool is_collision) {
   const CoalScalar prec = 1e-12;
@@ -403,13 +403,13 @@ bool shapeDistance(const GJKSolver* nsolver, const CollisionRequest& request,
                    const Convex<Polygone>& convex1,
                    const int convex1_active_faces,
                    const Convex<Polygone>& convex2,
-                   const int convex2_active_faces, const Transform3f& tf1,
-                   const Shape& shape, const Transform3f& tf2,
+                   const int convex2_active_faces, const Transform3s& tf1,
+                   const Shape& shape, const Transform3s& tf2,
                    CoalScalar& distance, Vec3s& c1, Vec3s& c2, Vec3s& normal,
                    Vec3s& normal_top, bool& hfield_witness_is_on_bin_side) {
   enum { RTIsIdentity = Options & RelativeTransformationIsIdentity };
 
-  const Transform3f Id;
+  const Transform3s Id;
   // The solver `nsolver` has already been set up by the collision request
   // `request`. If GJK early stopping is enabled through `request`, it will be
   // used.
diff --git a/include/coal/internal/traversal_node_octree.h b/include/coal/internal/traversal_node_octree.h
index f9b49722ef015b777878ff1a4f939e230521ea08..2f9da5f074c1a3d84b44ccdbd3b0b9df26d3523c 100644
--- a/include/coal/internal/traversal_node_octree.h
+++ b/include/coal/internal/traversal_node_octree.h
@@ -74,7 +74,7 @@ class COAL_DLLAPI OcTreeSolver {
 
   /// @brief collision between two octrees
   void OcTreeIntersect(const OcTree* tree1, const OcTree* tree2,
-                       const Transform3f& tf1, const Transform3f& tf2,
+                       const Transform3s& tf1, const Transform3s& tf2,
                        const CollisionRequest& request_,
                        CollisionResult& result_) const {
     crequest = &request_;
@@ -86,7 +86,7 @@ class COAL_DLLAPI OcTreeSolver {
 
   /// @brief distance between two octrees
   void OcTreeDistance(const OcTree* tree1, const OcTree* tree2,
-                      const Transform3f& tf1, const Transform3f& tf2,
+                      const Transform3s& tf1, const Transform3s& tf2,
                       const DistanceRequest& request_,
                       DistanceResult& result_) const {
     drequest = &request_;
@@ -99,7 +99,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief collision between octree and mesh
   template <typename BV>
   void OcTreeMeshIntersect(const OcTree* tree1, const BVHModel<BV>* tree2,
-                           const Transform3f& tf1, const Transform3f& tf2,
+                           const Transform3s& tf1, const Transform3s& tf2,
                            const CollisionRequest& request_,
                            CollisionResult& result_) const {
     crequest = &request_;
@@ -112,7 +112,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief distance between octree and mesh
   template <typename BV>
   void OcTreeMeshDistance(const OcTree* tree1, const BVHModel<BV>* tree2,
-                          const Transform3f& tf1, const Transform3f& tf2,
+                          const Transform3s& tf1, const Transform3s& tf2,
                           const DistanceRequest& request_,
                           DistanceResult& result_) const {
     drequest = &request_;
@@ -125,7 +125,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief collision between mesh and octree
   template <typename BV>
   void MeshOcTreeIntersect(const BVHModel<BV>* tree1, const OcTree* tree2,
-                           const Transform3f& tf1, const Transform3f& tf2,
+                           const Transform3s& tf1, const Transform3s& tf2,
                            const CollisionRequest& request_,
                            CollisionResult& result_) const
 
@@ -140,7 +140,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief distance between mesh and octree
   template <typename BV>
   void MeshOcTreeDistance(const BVHModel<BV>* tree1, const OcTree* tree2,
-                          const Transform3f& tf1, const Transform3f& tf2,
+                          const Transform3s& tf1, const Transform3s& tf2,
                           const DistanceRequest& request_,
                           DistanceResult& result_) const {
     drequest = &request_;
@@ -152,8 +152,8 @@ class COAL_DLLAPI OcTreeSolver {
 
   template <typename BV>
   void OcTreeHeightFieldIntersect(
-      const OcTree* tree1, const HeightField<BV>* tree2, const Transform3f& tf1,
-      const Transform3f& tf2, const CollisionRequest& request_,
+      const OcTree* tree1, const HeightField<BV>* tree2, const Transform3s& tf1,
+      const Transform3s& tf2, const CollisionRequest& request_,
       CollisionResult& result_, CoalScalar& sqrDistLowerBound) const {
     crequest = &request_;
     cresult = &result_;
@@ -165,8 +165,8 @@ class COAL_DLLAPI OcTreeSolver {
 
   template <typename BV>
   void HeightFieldOcTreeIntersect(const HeightField<BV>* tree1,
-                                  const OcTree* tree2, const Transform3f& tf1,
-                                  const Transform3f& tf2,
+                                  const OcTree* tree2, const Transform3s& tf1,
+                                  const Transform3s& tf2,
                                   const CollisionRequest& request_,
                                   CollisionResult& result_,
                                   CoalScalar& sqrDistLowerBound) const {
@@ -181,14 +181,14 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief collision between octree and shape
   template <typename S>
   void OcTreeShapeIntersect(const OcTree* tree, const S& s,
-                            const Transform3f& tf1, const Transform3f& tf2,
+                            const Transform3s& tf1, const Transform3s& tf2,
                             const CollisionRequest& request_,
                             CollisionResult& result_) const {
     crequest = &request_;
     cresult = &result_;
 
     AABB bv2;
-    computeBV<AABB>(s, Transform3f(), bv2);
+    computeBV<AABB>(s, Transform3s(), bv2);
     OBB obb2;
     convertBV(bv2, tf2, obb2);
     OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
@@ -198,14 +198,14 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief collision between shape and octree
   template <typename S>
   void ShapeOcTreeIntersect(const S& s, const OcTree* tree,
-                            const Transform3f& tf1, const Transform3f& tf2,
+                            const Transform3s& tf1, const Transform3s& tf2,
                             const CollisionRequest& request_,
                             CollisionResult& result_) const {
     crequest = &request_;
     cresult = &result_;
 
     AABB bv1;
-    computeBV<AABB>(s, Transform3f(), bv1);
+    computeBV<AABB>(s, Transform3s(), bv1);
     OBB obb1;
     convertBV(bv1, tf1, obb1);
     OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
@@ -215,7 +215,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief distance between octree and shape
   template <typename S>
   void OcTreeShapeDistance(const OcTree* tree, const S& s,
-                           const Transform3f& tf1, const Transform3f& tf2,
+                           const Transform3s& tf1, const Transform3s& tf2,
                            const DistanceRequest& request_,
                            DistanceResult& result_) const {
     drequest = &request_;
@@ -230,7 +230,7 @@ class COAL_DLLAPI OcTreeSolver {
   /// @brief distance between shape and octree
   template <typename S>
   void ShapeOcTreeDistance(const S& s, const OcTree* tree,
-                           const Transform3f& tf1, const Transform3f& tf2,
+                           const Transform3s& tf1, const Transform3s& tf2,
                            const DistanceRequest& request_,
                            DistanceResult& result_) const {
     drequest = &request_;
@@ -247,12 +247,12 @@ class COAL_DLLAPI OcTreeSolver {
   bool OcTreeShapeDistanceRecurse(const OcTree* tree1,
                                   const OcTree::OcTreeNode* root1,
                                   const AABB& bv1, const S& s,
-                                  const AABB& aabb2, const Transform3f& tf1,
-                                  const Transform3f& tf2) const {
+                                  const AABB& aabb2, const Transform3s& tf1,
+                                  const Transform3s& tf2) const {
     if (!tree1->nodeHasChildren(root1)) {
       if (tree1->isNodeOccupied(root1)) {
         Box box;
-        Transform3f box_tf;
+        Transform3s box_tf;
         constructBox(bv1, tf1, box, box_tf);
 
         if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
@@ -299,8 +299,8 @@ class COAL_DLLAPI OcTreeSolver {
   bool OcTreeShapeIntersectRecurse(const OcTree* tree1,
                                    const OcTree::OcTreeNode* root1,
                                    const AABB& bv1, const S& s, const OBB& obb2,
-                                   const Transform3f& tf1,
-                                   const Transform3f& tf2) const {
+                                   const Transform3s& tf1,
+                                   const Transform3s& tf2) const {
     // Empty OcTree is considered free.
     if (!root1) return false;
 
@@ -327,7 +327,7 @@ class COAL_DLLAPI OcTreeSolver {
       assert(tree1->isNodeOccupied(root1));  // it isn't free nor uncertain.
 
       Box box;
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(bv1, tf1, box, box_tf);
       if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
         box.computeLocalAABB();
@@ -371,12 +371,12 @@ class COAL_DLLAPI OcTreeSolver {
   bool OcTreeMeshDistanceRecurse(const OcTree* tree1,
                                  const OcTree::OcTreeNode* root1,
                                  const AABB& bv1, const BVHModel<BV>* tree2,
-                                 unsigned int root2, const Transform3f& tf1,
-                                 const Transform3f& tf2) const {
+                                 unsigned int root2, const Transform3s& tf1,
+                                 const Transform3s& tf2) const {
     if (!tree1->nodeHasChildren(root1) && tree2->getBV(root2).isLeaf()) {
       if (tree1->isNodeOccupied(root1)) {
         Box box;
-        Transform3f box_tf;
+        Transform3s box_tf;
         constructBox(bv1, tf1, box, box_tf);
 
         if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
@@ -462,8 +462,8 @@ class COAL_DLLAPI OcTreeSolver {
   bool OcTreeMeshIntersectRecurse(const OcTree* tree1,
                                   const OcTree::OcTreeNode* root1,
                                   const AABB& bv1, const BVHModel<BV>* tree2,
-                                  unsigned int root2, const Transform3f& tf1,
-                                  const Transform3f& tf2) const {
+                                  unsigned int root2, const Transform3s& tf1,
+                                  const Transform3s& tf2) const {
     // FIXME(jmirabel) I do not understand why the BVHModel was traversed. The
     // code in this if(!root1) did not output anything so the empty OcTree is
     // considered free. Should an empty OcTree be considered free ?
@@ -496,7 +496,7 @@ class COAL_DLLAPI OcTreeSolver {
     if (!tree1->nodeHasChildren(root1) && bvn2.isLeaf()) {
       assert(tree1->isNodeOccupied(root1));  // it isn't free nor uncertain.
       Box box;
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(bv1, tf1, box, box_tf);
       if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
         box.computeLocalAABB();
@@ -566,8 +566,8 @@ class COAL_DLLAPI OcTreeSolver {
   template <typename BV>
   bool OcTreeHeightFieldIntersectRecurse(
       const OcTree* tree1, const OcTree::OcTreeNode* root1, const AABB& bv1,
-      const HeightField<BV>* tree2, unsigned int root2, const Transform3f& tf1,
-      const Transform3f& tf2, CoalScalar& sqrDistLowerBound) const {
+      const HeightField<BV>* tree2, unsigned int root2, const Transform3s& tf1,
+      const Transform3s& tf2, CoalScalar& sqrDistLowerBound) const {
     // FIXME(jmirabel) I do not understand why the BVHModel was traversed. The
     // code in this if(!root1) did not output anything so the empty OcTree is
     // considered free. Should an empty OcTree be considered free ?
@@ -602,7 +602,7 @@ class COAL_DLLAPI OcTreeSolver {
     if (!tree1->nodeHasChildren(root1) && bvn2.isLeaf()) {
       assert(tree1->isNodeOccupied(root1));  // it isn't free nor uncertain.
       Box box;
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(bv1, tf1, box, box_tf);
       if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
         box.computeLocalAABB();
@@ -686,8 +686,8 @@ class COAL_DLLAPI OcTreeSolver {
   template <typename BV>
   bool HeightFieldOcTreeIntersectRecurse(
       const HeightField<BV>* tree1, unsigned int root1, const OcTree* tree2,
-      const OcTree::OcTreeNode* root2, const AABB& bv2, const Transform3f& tf1,
-      const Transform3f& tf2, CoalScalar& sqrDistLowerBound) const {
+      const OcTree::OcTreeNode* root2, const AABB& bv2, const Transform3s& tf1,
+      const Transform3s& tf2, CoalScalar& sqrDistLowerBound) const {
     // FIXME(jmirabel) I do not understand why the BVHModel was traversed. The
     // code in this if(!root1) did not output anything so the empty OcTree is
     // considered free. Should an empty OcTree be considered free ?
@@ -722,7 +722,7 @@ class COAL_DLLAPI OcTreeSolver {
     if (!tree2->nodeHasChildren(root2) && bvn1.isLeaf()) {
       assert(tree2->isNodeOccupied(root2));  // it isn't free nor uncertain.
       Box box;
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(bv2, tf2, box, box_tf);
       if (solver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
         box.computeLocalAABB();
@@ -806,12 +806,12 @@ class COAL_DLLAPI OcTreeSolver {
                              const OcTree::OcTreeNode* root1, const AABB& bv1,
                              const OcTree* tree2,
                              const OcTree::OcTreeNode* root2, const AABB& bv2,
-                             const Transform3f& tf1,
-                             const Transform3f& tf2) const {
+                             const Transform3s& tf1,
+                             const Transform3s& tf2) const {
     if (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2)) {
       if (tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2)) {
         Box box1, box2;
-        Transform3f box1_tf, box2_tf;
+        Transform3s box1_tf, box2_tf;
         constructBox(bv1, tf1, box1, box1_tf);
         constructBox(bv2, tf2, box2, box2_tf);
 
@@ -887,8 +887,8 @@ class COAL_DLLAPI OcTreeSolver {
                               const OcTree::OcTreeNode* root1, const AABB& bv1,
                               const OcTree* tree2,
                               const OcTree::OcTreeNode* root2, const AABB& bv2,
-                              const Transform3f& tf1,
-                              const Transform3f& tf2) const {
+                              const Transform3s& tf1,
+                              const Transform3s& tf2) const {
     // Empty OcTree is considered free.
     if (!root1) return false;
     if (!root2) return false;
@@ -931,7 +931,7 @@ class COAL_DLLAPI OcTreeSolver {
       assert(tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2));
 
       Box box1, box2;
-      Transform3f box1_tf, box2_tf;
+      Transform3s box1_tf, box2_tf;
       constructBox(bv1, tf1, box1, box1_tf);
       constructBox(bv2, tf2, box2, box2_tf);
 
@@ -1028,7 +1028,7 @@ class COAL_DLLAPI OcTreeCollisionTraversalNode
   const OcTree* model1;
   const OcTree* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1060,7 +1060,7 @@ class COAL_DLLAPI ShapeOcTreeCollisionTraversalNode
   const S* model1;
   const OcTree* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1093,7 +1093,7 @@ class COAL_DLLAPI OcTreeShapeCollisionTraversalNode
   const OcTree* model1;
   const S* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1125,7 +1125,7 @@ class COAL_DLLAPI MeshOcTreeCollisionTraversalNode
   const BVHModel<BV>* model1;
   const OcTree* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1157,7 +1157,7 @@ class COAL_DLLAPI OcTreeMeshCollisionTraversalNode
   const OcTree* model1;
   const BVHModel<BV>* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1188,7 +1188,7 @@ class COAL_DLLAPI OcTreeHeightFieldCollisionTraversalNode
   const OcTree* model1;
   const HeightField<BV>* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
@@ -1219,7 +1219,7 @@ class COAL_DLLAPI HeightFieldOcTreeCollisionTraversalNode
   const HeightField<BV>* model1;
   const OcTree* model2;
 
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
 
   const OcTreeSolver* otsolver;
 };
diff --git a/include/coal/internal/traversal_node_setup.h b/include/coal/internal/traversal_node_setup.h
index 6f60609e8001feac46a394d7f77ee415275284df..4f892a02ab5b7ccd1808cd25b4ec646c1462fc0e 100644
--- a/include/coal/internal/traversal_node_setup.h
+++ b/include/coal/internal/traversal_node_setup.h
@@ -61,8 +61,8 @@ namespace coal {
 /// @brief Initialize traversal node for collision between two octrees, given
 /// current object transform
 inline bool initialize(OcTreeCollisionTraversalNode& node, const OcTree& model1,
-                       const Transform3f& tf1, const OcTree& model2,
-                       const Transform3f& tf2, const OcTreeSolver* otsolver,
+                       const Transform3s& tf1, const OcTree& model2,
+                       const Transform3s& tf2, const OcTreeSolver* otsolver,
                        CollisionResult& result) {
   node.result = &result;
 
@@ -80,8 +80,8 @@ inline bool initialize(OcTreeCollisionTraversalNode& node, const OcTree& model1,
 /// @brief Initialize traversal node for distance between two octrees, given
 /// current object transform
 inline bool initialize(OcTreeDistanceTraversalNode& node, const OcTree& model1,
-                       const Transform3f& tf1, const OcTree& model2,
-                       const Transform3f& tf2, const OcTreeSolver* otsolver,
+                       const Transform3s& tf1, const OcTree& model2,
+                       const Transform3s& tf2, const OcTreeSolver* otsolver,
                        const DistanceRequest& request, DistanceResult& result)
 
 {
@@ -103,8 +103,8 @@ inline bool initialize(OcTreeDistanceTraversalNode& node, const OcTree& model1,
 /// octree, given current object transform
 template <typename S>
 bool initialize(ShapeOcTreeCollisionTraversalNode<S>& node, const S& model1,
-                const Transform3f& tf1, const OcTree& model2,
-                const Transform3f& tf2, const OcTreeSolver* otsolver,
+                const Transform3s& tf1, const OcTree& model2,
+                const Transform3s& tf2, const OcTreeSolver* otsolver,
                 CollisionResult& result) {
   node.result = &result;
 
@@ -123,8 +123,8 @@ bool initialize(ShapeOcTreeCollisionTraversalNode<S>& node, const S& model1,
 /// shape, given current object transform
 template <typename S>
 bool initialize(OcTreeShapeCollisionTraversalNode<S>& node,
-                const OcTree& model1, const Transform3f& tf1, const S& model2,
-                const Transform3f& tf2, const OcTreeSolver* otsolver,
+                const OcTree& model1, const Transform3s& tf1, const S& model2,
+                const Transform3s& tf2, const OcTreeSolver* otsolver,
                 CollisionResult& result) {
   node.result = &result;
 
@@ -143,8 +143,8 @@ bool initialize(OcTreeShapeCollisionTraversalNode<S>& node,
 /// octree, given current object transform
 template <typename S>
 bool initialize(ShapeOcTreeDistanceTraversalNode<S>& node, const S& model1,
-                const Transform3f& tf1, const OcTree& model2,
-                const Transform3f& tf2, const OcTreeSolver* otsolver,
+                const Transform3s& tf1, const OcTree& model2,
+                const Transform3s& tf2, const OcTreeSolver* otsolver,
                 const DistanceRequest& request, DistanceResult& result) {
   node.request = request;
   node.result = &result;
@@ -164,7 +164,7 @@ bool initialize(ShapeOcTreeDistanceTraversalNode<S>& node, const S& model1,
 /// shape, given current object transform
 template <typename S>
 bool initialize(OcTreeShapeDistanceTraversalNode<S>& node, const OcTree& model1,
-                const Transform3f& tf1, const S& model2, const Transform3f& tf2,
+                const Transform3s& tf1, const S& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, const DistanceRequest& request,
                 DistanceResult& result) {
   node.request = request;
@@ -185,8 +185,8 @@ bool initialize(OcTreeShapeDistanceTraversalNode<S>& node, const OcTree& model1,
 /// octree, given current object transform
 template <typename BV>
 bool initialize(MeshOcTreeCollisionTraversalNode<BV>& node,
-                const BVHModel<BV>& model1, const Transform3f& tf1,
-                const OcTree& model2, const Transform3f& tf2,
+                const BVHModel<BV>& model1, const Transform3s& tf1,
+                const OcTree& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, CollisionResult& result) {
   node.result = &result;
 
@@ -205,8 +205,8 @@ bool initialize(MeshOcTreeCollisionTraversalNode<BV>& node,
 /// mesh, given current object transform
 template <typename BV>
 bool initialize(OcTreeMeshCollisionTraversalNode<BV>& node,
-                const OcTree& model1, const Transform3f& tf1,
-                const BVHModel<BV>& model2, const Transform3f& tf2,
+                const OcTree& model1, const Transform3s& tf1,
+                const BVHModel<BV>& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, CollisionResult& result) {
   node.result = &result;
 
@@ -225,8 +225,8 @@ bool initialize(OcTreeMeshCollisionTraversalNode<BV>& node,
 /// height field, given current object transform
 template <typename BV>
 bool initialize(OcTreeHeightFieldCollisionTraversalNode<BV>& node,
-                const OcTree& model1, const Transform3f& tf1,
-                const HeightField<BV>& model2, const Transform3f& tf2,
+                const OcTree& model1, const Transform3s& tf1,
+                const HeightField<BV>& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, CollisionResult& result) {
   node.result = &result;
 
@@ -245,8 +245,8 @@ bool initialize(OcTreeHeightFieldCollisionTraversalNode<BV>& node,
 /// one octree, given current object transform
 template <typename BV>
 bool initialize(HeightFieldOcTreeCollisionTraversalNode<BV>& node,
-                const HeightField<BV>& model1, const Transform3f& tf1,
-                const OcTree& model2, const Transform3f& tf2,
+                const HeightField<BV>& model1, const Transform3s& tf1,
+                const OcTree& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, CollisionResult& result) {
   node.result = &result;
 
@@ -265,8 +265,8 @@ bool initialize(HeightFieldOcTreeCollisionTraversalNode<BV>& node,
 /// octree, given current object transform
 template <typename BV>
 bool initialize(MeshOcTreeDistanceTraversalNode<BV>& node,
-                const BVHModel<BV>& model1, const Transform3f& tf1,
-                const OcTree& model2, const Transform3f& tf2,
+                const BVHModel<BV>& model1, const Transform3s& tf1,
+                const OcTree& model2, const Transform3s& tf2,
                 const OcTreeSolver* otsolver, const DistanceRequest& request,
                 DistanceResult& result) {
   node.request = request;
@@ -287,8 +287,8 @@ bool initialize(MeshOcTreeDistanceTraversalNode<BV>& node,
 /// mesh, given current object transform
 template <typename BV>
 bool initialize(OcTreeMeshDistanceTraversalNode<BV>& node, const OcTree& model1,
-                const Transform3f& tf1, const BVHModel<BV>& model2,
-                const Transform3f& tf2, const OcTreeSolver* otsolver,
+                const Transform3s& tf1, const BVHModel<BV>& model2,
+                const Transform3s& tf2, const OcTreeSolver* otsolver,
                 const DistanceRequest& request, DistanceResult& result) {
   node.request = request;
   node.result = &result;
@@ -310,8 +310,8 @@ bool initialize(OcTreeMeshDistanceTraversalNode<BV>& node, const OcTree& model1,
 /// given current object transform
 template <typename S1, typename S2>
 bool initialize(ShapeCollisionTraversalNode<S1, S2>& node, const S1& shape1,
-                const Transform3f& tf1, const S2& shape2,
-                const Transform3f& tf2, const GJKSolver* nsolver,
+                const Transform3s& tf1, const S2& shape2,
+                const Transform3s& tf2, const GJKSolver* nsolver,
                 CollisionResult& result) {
   node.model1 = &shape1;
   node.tf1 = tf1;
@@ -328,8 +328,8 @@ bool initialize(ShapeCollisionTraversalNode<S1, S2>& node, const S1& shape1,
 /// shape, given current object transform
 template <typename BV, typename S>
 bool initialize(MeshShapeCollisionTraversalNode<BV, S>& node,
-                BVHModel<BV>& model1, Transform3f& tf1, const S& model2,
-                const Transform3f& tf2, const GJKSolver* nsolver,
+                BVHModel<BV>& model1, Transform3s& tf1, const S& model2,
+                const Transform3s& tf2, const GJKSolver* nsolver,
                 CollisionResult& result, bool use_refit = false,
                 bool refit_bottomup = false) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
@@ -376,8 +376,8 @@ bool initialize(MeshShapeCollisionTraversalNode<BV, S>& node,
 /// 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 BVHModel<BV>& model1, const Transform3s& tf1,
+                const S& model2, const Transform3s& tf2,
                 const GJKSolver* nsolver, CollisionResult& result) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -405,8 +405,8 @@ bool initialize(MeshShapeCollisionTraversalNode<BV, S, 0>& node,
 /// shape, given current object transform
 template <typename BV, typename S>
 bool initialize(HeightFieldShapeCollisionTraversalNode<BV, S>& node,
-                HeightField<BV>& model1, Transform3f& tf1, const S& model2,
-                const Transform3f& tf2, const GJKSolver* nsolver,
+                HeightField<BV>& model1, Transform3s& tf1, const S& model2,
+                const Transform3s& tf2, const GJKSolver* nsolver,
                 CollisionResult& result, bool use_refit = false,
                 bool refit_bottomup = false);
 
@@ -414,8 +414,8 @@ bool initialize(HeightFieldShapeCollisionTraversalNode<BV, S>& node,
 /// shape
 template <typename BV, typename S>
 bool initialize(HeightFieldShapeCollisionTraversalNode<BV, S, 0>& node,
-                const HeightField<BV>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
+                const HeightField<BV>& model1, const Transform3s& tf1,
+                const S& model2, const Transform3s& tf2,
                 const GJKSolver* nsolver, CollisionResult& result) {
   node.model1 = &model1;
   node.tf1 = tf1;
@@ -434,8 +434,8 @@ bool initialize(HeightFieldShapeCollisionTraversalNode<BV, S, 0>& node,
 namespace details {
 template <typename S, typename BV, template <typename> class OrientedNode>
 static inline bool setupShapeMeshCollisionOrientedNode(
-    OrientedNode<S>& node, const S& model1, const Transform3f& tf1,
-    const BVHModel<BV>& model2, const Transform3f& tf2,
+    OrientedNode<S>& node, const S& model1, const Transform3s& tf1,
+    const BVHModel<BV>& model2, const Transform3s& tf2,
     const GJKSolver* nsolver, CollisionResult& result) {
   if (model2.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -466,8 +466,8 @@ static inline bool setupShapeMeshCollisionOrientedNode(
 template <typename BV>
 bool initialize(
     MeshCollisionTraversalNode<BV, RelativeTransformationIsIdentity>& node,
-    BVHModel<BV>& model1, Transform3f& tf1, BVHModel<BV>& model2,
-    Transform3f& tf2, CollisionResult& result, bool use_refit = false,
+    BVHModel<BV>& model1, Transform3s& tf1, BVHModel<BV>& model2,
+    Transform3s& tf2, CollisionResult& result, bool use_refit = false,
     bool refit_bottomup = false) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -530,8 +530,8 @@ bool initialize(
 
 template <typename BV>
 bool initialize(MeshCollisionTraversalNode<BV, 0>& node,
-                const BVHModel<BV>& model1, const Transform3f& tf1,
-                const BVHModel<BV>& model2, const Transform3f& tf2,
+                const BVHModel<BV>& model1, const Transform3s& tf1,
+                const BVHModel<BV>& model2, const Transform3s& tf2,
                 CollisionResult& result) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -567,8 +567,8 @@ bool initialize(MeshCollisionTraversalNode<BV, 0>& node,
 /// @brief Initialize traversal node for distance between two geometric shapes
 template <typename S1, typename S2>
 bool initialize(ShapeDistanceTraversalNode<S1, S2>& node, const S1& shape1,
-                const Transform3f& tf1, const S2& shape2,
-                const Transform3f& tf2, const GJKSolver* nsolver,
+                const Transform3s& tf1, const S2& shape2,
+                const Transform3s& tf2, const GJKSolver* nsolver,
                 const DistanceRequest& request, DistanceResult& result) {
   node.request = request;
   node.result = &result;
@@ -587,8 +587,8 @@ bool initialize(ShapeDistanceTraversalNode<S1, S2>& node, const S1& shape1,
 template <typename BV>
 bool initialize(
     MeshDistanceTraversalNode<BV, RelativeTransformationIsIdentity>& node,
-    BVHModel<BV>& model1, Transform3f& tf1, BVHModel<BV>& model2,
-    Transform3f& tf2, const DistanceRequest& request, DistanceResult& result,
+    BVHModel<BV>& model1, Transform3s& tf1, BVHModel<BV>& model2,
+    Transform3s& tf2, const DistanceRequest& request, DistanceResult& result,
     bool use_refit = false, bool refit_bottomup = false) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -653,8 +653,8 @@ bool initialize(
 /// @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 BVHModel<BV>& model1, const Transform3s& tf1,
+                const BVHModel<BV>& model2, const Transform3s& tf2,
                 const DistanceRequest& request, DistanceResult& result) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -696,8 +696,8 @@ bool initialize(MeshDistanceTraversalNode<BV, 0>& node,
 /// and one shape, given the current transforms
 template <typename BV, typename S>
 bool initialize(MeshShapeDistanceTraversalNode<BV, S>& node,
-                BVHModel<BV>& model1, Transform3f& tf1, const S& model2,
-                const Transform3f& tf2, const GJKSolver* nsolver,
+                BVHModel<BV>& model1, Transform3s& tf1, const S& model2,
+                const Transform3s& tf2, const GJKSolver* nsolver,
                 const DistanceRequest& request, DistanceResult& result,
                 bool use_refit = false, bool refit_bottomup = false) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
@@ -744,8 +744,8 @@ namespace details {
 
 template <typename BV, typename S, template <typename> class OrientedNode>
 static inline bool setupMeshShapeDistanceOrientedNode(
-    OrientedNode<S>& node, const BVHModel<BV>& model1, const Transform3f& tf1,
-    const S& model2, const Transform3f& tf2, const GJKSolver* nsolver,
+    OrientedNode<S>& node, const BVHModel<BV>& model1, const Transform3s& tf1,
+    const S& model2, const Transform3s& tf2, const GJKSolver* nsolver,
     const DistanceRequest& request, DistanceResult& result) {
   if (model1.getModelType() != BVH_MODEL_TRIANGLES)
     COAL_THROW_PRETTY(
@@ -776,8 +776,8 @@ static inline bool setupMeshShapeDistanceOrientedNode(
 /// and one shape, specialized for RSS type
 template <typename S>
 bool initialize(MeshShapeDistanceTraversalNodeRSS<S>& node,
-                const BVHModel<RSS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
+                const BVHModel<RSS>& model1, const Transform3s& tf1,
+                const S& model2, const Transform3s& tf2,
                 const GJKSolver* nsolver, const DistanceRequest& request,
                 DistanceResult& result) {
   return details::setupMeshShapeDistanceOrientedNode(
@@ -788,8 +788,8 @@ bool initialize(MeshShapeDistanceTraversalNodeRSS<S>& node,
 /// and one shape, specialized for kIOS type
 template <typename S>
 bool initialize(MeshShapeDistanceTraversalNodekIOS<S>& node,
-                const BVHModel<kIOS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
+                const BVHModel<kIOS>& model1, const Transform3s& tf1,
+                const S& model2, const Transform3s& tf2,
                 const GJKSolver* nsolver, const DistanceRequest& request,
                 DistanceResult& result) {
   return details::setupMeshShapeDistanceOrientedNode(
@@ -800,8 +800,8 @@ bool initialize(MeshShapeDistanceTraversalNodekIOS<S>& node,
 /// and one shape, specialized for OBBRSS type
 template <typename S>
 bool initialize(MeshShapeDistanceTraversalNodeOBBRSS<S>& node,
-                const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
-                const S& model2, const Transform3f& tf2,
+                const BVHModel<OBBRSS>& model1, const Transform3s& tf1,
+                const S& model2, const Transform3s& tf2,
                 const GJKSolver* nsolver, const DistanceRequest& request,
                 DistanceResult& result) {
   return details::setupMeshShapeDistanceOrientedNode(
diff --git a/include/coal/math/transform.h b/include/coal/math/transform.h
index ff96bac1f383bcb20134abf5d81df388807b2dca..d2cf8ed41e41ab42b4172af4a59909e65cd6ef3d 100644
--- a/include/coal/math/transform.h
+++ b/include/coal/math/transform.h
@@ -52,7 +52,7 @@ static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) {
 }
 
 /// @brief Simple transform class used locally by InterpMotion
-class COAL_DLLAPI Transform3f {
+class COAL_DLLAPI Transform3s {
   /// @brief Matrix cache
   Matrix3s R;
 
@@ -61,37 +61,37 @@ class COAL_DLLAPI Transform3f {
 
  public:
   /// @brief Default transform is no movement
-  Transform3f() {
+  Transform3s() {
     setIdentity();  // set matrix_set true
   }
 
-  static Transform3f Identity() { return Transform3f(); }
+  static Transform3s Identity() { return Transform3s(); }
 
   /// @brief Construct transform from rotation and translation
   template <typename Matrixx3Like, typename Vector3Like>
-  Transform3f(const Eigen::MatrixBase<Matrixx3Like>& R_,
+  Transform3s(const Eigen::MatrixBase<Matrixx3Like>& R_,
               const Eigen::MatrixBase<Vector3Like>& T_)
       : R(R_), T(T_) {}
 
   /// @brief Construct transform from rotation and translation
   template <typename Vector3Like>
-  Transform3f(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
+  Transform3s(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
       : R(q_.toRotationMatrix()), T(T_) {}
 
   /// @brief Construct transform from rotation
-  Transform3f(const Matrix3s& R_) : R(R_), T(Vec3s::Zero()) {}
+  Transform3s(const Matrix3s& R_) : R(R_), T(Vec3s::Zero()) {}
 
   /// @brief Construct transform from rotation
-  Transform3f(const Quatf& q_) : R(q_), T(Vec3s::Zero()) {}
+  Transform3s(const Quatf& q_) : R(q_), T(Vec3s::Zero()) {}
 
   /// @brief Construct transform from translation
-  Transform3f(const Vec3s& T_) : R(Matrix3s::Identity()), T(T_) {}
+  Transform3s(const Vec3s& T_) : R(Matrix3s::Identity()), T(T_) {}
 
   /// @brief Construct transform from other transform
-  Transform3f(const Transform3f& tf) : R(tf.R), T(tf.T) {}
+  Transform3s(const Transform3s& tf) : R(tf.R), T(tf.T) {}
 
   /// @brief operator =
-  Transform3f& operator=(const Transform3f& tf) {
+  Transform3s& operator=(const Transform3s& tf) {
     R = tf.R;
     T = tf.T;
     return *this;
@@ -160,32 +160,32 @@ class COAL_DLLAPI Transform3f {
   }
 
   /// @brief inverse transform
-  inline Transform3f& inverseInPlace() {
+  inline Transform3s& inverseInPlace() {
     R.transposeInPlace();
     T = -R * T;
     return *this;
   }
 
   /// @brief inverse transform
-  inline Transform3f inverse() {
-    return Transform3f(R.transpose(), -R.transpose() * T);
+  inline Transform3s inverse() {
+    return Transform3s(R.transpose(), -R.transpose() * T);
   }
 
   /// @brief inverse the transform and multiply with another
-  inline Transform3f inverseTimes(const Transform3f& other) const {
-    return Transform3f(R.transpose() * other.R, R.transpose() * (other.T - T));
+  inline Transform3s inverseTimes(const Transform3s& other) const {
+    return Transform3s(R.transpose() * other.R, R.transpose() * (other.T - T));
   }
 
   /// @brief multiply with another transform
-  inline const Transform3f& operator*=(const Transform3f& other) {
+  inline const Transform3s& operator*=(const Transform3s& other) {
     T += R * other.T;
     R *= other.R;
     return *this;
   }
 
   /// @brief multiply with another transform
-  inline Transform3f operator*(const Transform3f& other) const {
-    return Transform3f(R * other.R, R * other.T + T);
+  inline Transform3s operator*(const Transform3s& other) const {
+    return Transform3s(R * other.R, R * other.T + T);
   }
 
   /// @brief check whether the transform is identity
@@ -202,16 +202,16 @@ class COAL_DLLAPI Transform3f {
   }
 
   /// @brief return a random transform
-  static Transform3f Random() { return Transform3f().setRandom(); }
+  static Transform3s Random() { return Transform3s().setRandom(); }
 
   /// @brief set the transform to a random transform
-  Transform3f& setRandom();
+  Transform3s& setRandom();
 
-  bool operator==(const Transform3f& other) const {
+  bool operator==(const Transform3s& other) const {
     return (R == other.getRotation()) && (T == other.getTranslation());
   }
 
-  bool operator!=(const Transform3f& other) const { return !(*this == other); }
+  bool operator!=(const Transform3s& other) const { return !(*this == other); }
 
   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 };
@@ -247,7 +247,7 @@ inline Quatf uniformRandomQuaternion() {
   return q;
 }
 
-inline Transform3f& Transform3f::setRandom() {
+inline Transform3s& Transform3s::setRandom() {
   const Quatf q = uniformRandomQuaternion();
   this->rotation() = q.matrix();
   this->translation().setRandom();
diff --git a/include/coal/narrowphase/minkowski_difference.h b/include/coal/narrowphase/minkowski_difference.h
index 3449301ab66c69f368147ee3fe1f7525c30c9bae..1d9e36bfa36f0ed1a64536cad5ac5922f4106917 100644
--- a/include/coal/narrowphase/minkowski_difference.h
+++ b/include/coal/narrowphase/minkowski_difference.h
@@ -127,7 +127,7 @@ struct COAL_DLLAPI MinkowskiDiff {
   /// ShapeBase*)` for more details.
   template <int _SupportOptions = SupportOptions::NoSweptSphere>
   void set(const ShapeBase* shape0, const ShapeBase* shape1,
-           const Transform3f& tf0, const Transform3f& tf1);
+           const Transform3s& tf0, const Transform3s& tf1);
 
   /// @brief support function for shape0.
   /// The output vector is expressed in the local frame of shape0.
diff --git a/include/coal/narrowphase/narrowphase.h b/include/coal/narrowphase/narrowphase.h
index 03046b45e41b043a67e8a654e2a37ffd66a75cc6..65cd31b13c7480c343128efd67090b37a26cd632 100644
--- a/include/coal/narrowphase/narrowphase.h
+++ b/include/coal/narrowphase/narrowphase.h
@@ -305,8 +305,8 @@ struct COAL_DLLAPI GJKSolver {
   /// It's up to the user to decide whether the shapes are in collision or not,
   /// based on that estimate.
   template <typename S1, typename S2>
-  CoalScalar shapeDistance(const S1& s1, const Transform3f& tf1, const S2& s2,
-                           const Transform3f& tf2,
+  CoalScalar shapeDistance(const S1& s1, const Transform3s& tf1, const S2& s2,
+                           const Transform3s& tf2,
                            const bool compute_penetration, Vec3s& p1, Vec3s& p2,
                            Vec3s& normal) const {
     constexpr bool relative_transformation_already_computed = false;
@@ -320,11 +320,11 @@ struct COAL_DLLAPI GJKSolver {
   /// second shape is a triangle. It is more efficient to pre-compute the
   /// relative transformation between the two shapes before calling GJK/EPA.
   template <typename S1>
-  CoalScalar shapeDistance(const S1& s1, const Transform3f& tf1,
-                           const TriangleP& s2, const Transform3f& tf2,
+  CoalScalar shapeDistance(const S1& s1, const Transform3s& tf1,
+                           const TriangleP& s2, const Transform3s& tf2,
                            const bool compute_penetration, Vec3s& p1, Vec3s& p2,
                            Vec3s& normal) const {
-    const Transform3f tf_1M2(tf1.inverseTimes(tf2));
+    const Transform3s tf_1M2(tf1.inverseTimes(tf2));
     TriangleP tri(tf_1M2.transform(s2.a), tf_1M2.transform(s2.b),
                   tf_1M2.transform(s2.c));
 
@@ -337,8 +337,8 @@ struct COAL_DLLAPI GJKSolver {
 
   /// @brief See other partial template specialization of shapeDistance above.
   template <typename S2>
-  CoalScalar shapeDistance(const TriangleP& s1, const Transform3f& tf1,
-                           const S2& s2, const Transform3f& tf2,
+  CoalScalar shapeDistance(const TriangleP& s1, const Transform3s& tf1,
+                           const S2& s2, const Transform3s& tf2,
                            const bool compute_penetration, Vec3s& p1, Vec3s& p2,
                            Vec3s& normal) const {
     CoalScalar distance = this->shapeDistance<S2>(
@@ -420,8 +420,8 @@ struct COAL_DLLAPI GJKSolver {
   template <typename S1, typename S2,
             int _SupportOptions = details::SupportOptions::NoSweptSphere>
   void runGJKAndEPA(
-      const S1& s1, const Transform3f& tf1, const S2& s2,
-      const Transform3f& tf2, const bool compute_penetration,
+      const S1& s1, const Transform3s& tf1, const S2& s2,
+      const Transform3s& tf2, const bool compute_penetration,
       CoalScalar& distance, Vec3s& p1, Vec3s& p2, Vec3s& normal,
       const bool relative_transformation_already_computed = false) const {
     // Reset internal state of GJK algorithm
@@ -586,7 +586,7 @@ struct COAL_DLLAPI GJKSolver {
     }
   }
 
-  void GJKEarlyStopExtractWitnessPointsAndNormal(const Transform3f& tf1,
+  void GJKEarlyStopExtractWitnessPointsAndNormal(const Transform3s& tf1,
                                                  CoalScalar& distance,
                                                  Vec3s& p1, Vec3s& p2,
                                                  Vec3s& normal) const {
@@ -607,7 +607,7 @@ struct COAL_DLLAPI GJKSolver {
     // normal = tf1.getRotation() * normal;
   }
 
-  void GJKExtractWitnessPointsAndNormal(const Transform3f& tf1,
+  void GJKExtractWitnessPointsAndNormal(const Transform3s& tf1,
                                         CoalScalar& distance, Vec3s& p1,
                                         Vec3s& p2, Vec3s& normal) const {
     // Apart from early stopping, there are two cases where GJK says there is no
@@ -634,7 +634,7 @@ struct COAL_DLLAPI GJKSolver {
     p2.noalias() = p + 0.5 * distance * normal;
   }
 
-  void GJKCollisionExtractWitnessPointsAndNormal(const Transform3f& tf1,
+  void GJKCollisionExtractWitnessPointsAndNormal(const Transform3s& tf1,
                                                  CoalScalar& distance,
                                                  Vec3s& p1, Vec3s& p2,
                                                  Vec3s& normal) const {
@@ -654,7 +654,7 @@ struct COAL_DLLAPI GJKSolver {
         Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
   }
 
-  void EPAExtractWitnessPointsAndNormal(const Transform3f& tf1,
+  void EPAExtractWitnessPointsAndNormal(const Transform3s& tf1,
                                         CoalScalar& distance, Vec3s& p1,
                                         Vec3s& p2, Vec3s& normal) const {
     // Cache EPA result for potential future call to this GJKSolver.
@@ -709,7 +709,7 @@ struct COAL_DLLAPI GJKSolver {
     p2.noalias() = p + 0.5 * distance * normal;
   }
 
-  void EPAFailedExtractWitnessPointsAndNormal(const Transform3f& tf1,
+  void EPAFailedExtractWitnessPointsAndNormal(const Transform3s& tf1,
                                               CoalScalar& distance, Vec3s& p1,
                                               Vec3s& p2, Vec3s& normal) const {
     this->cached_guess = Vec3s(1, 0, 0);
diff --git a/include/coal/serialization/transform.h b/include/coal/serialization/transform.h
index e2905e999e0668baf2aedceca780431eca5fe4fe..c43542d7a8a0a677735c399bc1879c05d448b534 100644
--- a/include/coal/serialization/transform.h
+++ b/include/coal/serialization/transform.h
@@ -12,7 +12,7 @@ namespace boost {
 namespace serialization {
 
 template <class Archive>
-void serialize(Archive& ar, coal::Transform3f& tf,
+void serialize(Archive& ar, coal::Transform3s& tf,
                const unsigned int /*version*/) {
   ar& make_nvp("R", tf.rotation());
   ar& make_nvp("T", tf.translation());
diff --git a/include/coal/shape/geometric_shape_to_BVH_model.h b/include/coal/shape/geometric_shape_to_BVH_model.h
index f9a3aca8bc8a0a8023d91e4e67ad2ce666ed8703..6f43e9d7d7db16a00b458dc26756e7e977d4d050 100644
--- a/include/coal/shape/geometric_shape_to_BVH_model.h
+++ b/include/coal/shape/geometric_shape_to_BVH_model.h
@@ -47,7 +47,7 @@ namespace coal {
 /// @brief Generate BVH model from box
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Box& shape,
-                      const Transform3f& pose) {
+                      const Transform3s& pose) {
   CoalScalar a = shape.halfSide[0];
   CoalScalar b = shape.halfSide[1];
   CoalScalar c = shape.halfSide[2];
@@ -89,7 +89,7 @@ void generateBVHModel(BVHModel<BV>& model, const Box& shape,
 /// longitude and number of rings along latitude.
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Sphere& shape,
-                      const Transform3f& pose, unsigned int seg,
+                      const Transform3s& pose, unsigned int seg,
                       unsigned int ring) {
   std::vector<Vec3s> points;
   std::vector<Triangle> tri_indices;
@@ -155,7 +155,7 @@ void generateBVHModel(BVHModel<BV>& model, const Sphere& shape,
 /// single triangle is approximately the same.s
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Sphere& shape,
-                      const Transform3f& pose,
+                      const Transform3s& pose,
                       unsigned int n_faces_for_unit_sphere) {
   CoalScalar r = shape.radius;
   CoalScalar n_low_bound =
@@ -170,7 +170,7 @@ void generateBVHModel(BVHModel<BV>& model, const Sphere& shape,
 /// circle and the number of segments along axis.
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Cylinder& shape,
-                      const Transform3f& pose, unsigned int tot,
+                      const Transform3s& pose, unsigned int tot,
                       unsigned int h_num) {
   std::vector<Vec3s> points;
   std::vector<Triangle> tri_indices;
@@ -243,7 +243,7 @@ void generateBVHModel(BVHModel<BV>& model, const Cylinder& shape,
 /// number of circle split number is r * tot.
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Cylinder& shape,
-                      const Transform3f& pose,
+                      const Transform3s& pose,
                       unsigned int tot_for_unit_cylinder) {
   CoalScalar r = shape.radius;
   CoalScalar h = 2 * shape.halfLength;
@@ -262,7 +262,7 @@ void generateBVHModel(BVHModel<BV>& model, const Cylinder& shape,
 /// circle and the number of segments along axis.
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Cone& shape,
-                      const Transform3f& pose, unsigned int tot,
+                      const Transform3s& pose, unsigned int tot,
                       unsigned int h_num) {
   std::vector<Vec3s> points;
   std::vector<Triangle> tri_indices;
@@ -335,7 +335,7 @@ void generateBVHModel(BVHModel<BV>& model, const Cone& shape,
 /// of circle split number is r * tot.
 template <typename BV>
 void generateBVHModel(BVHModel<BV>& model, const Cone& shape,
-                      const Transform3f& pose, unsigned int tot_for_unit_cone) {
+                      const Transform3s& pose, unsigned int tot_for_unit_cone) {
   CoalScalar r = shape.radius;
   CoalScalar h = 2 * shape.halfLength;
 
diff --git a/include/coal/shape/geometric_shapes.h b/include/coal/shape/geometric_shapes.h
index e88a737e9f27883d840d5ba5115b6335bab6d359..1050f692a6213034c3788587bfcfd6a95e381af5 100644
--- a/include/coal/shape/geometric_shapes.h
+++ b/include/coal/shape/geometric_shapes.h
@@ -125,10 +125,10 @@ class COAL_DLLAPI TriangleP : public ShapeBase {
 
   NODE_TYPE getNodeType() const { return GEOM_TRIANGLE; }
 
-  //  std::pair<ShapeBase*, Transform3f> inflated(const CoalScalar value) const
+  //  std::pair<ShapeBase*, Transform3s> inflated(const CoalScalar value) const
   //  {
   //    if (value == 0) return std::make_pair(new TriangleP(*this),
-  //    Transform3f()); Vec3s AB(b - a), BC(c - b), CA(a - c); AB.normalize();
+  //    Transform3s()); Vec3s AB(b - a), BC(c - b), CA(a - c); AB.normalize();
   //    BC.normalize();
   //    CA.normalize();
   //
@@ -137,7 +137,7 @@ class COAL_DLLAPI TriangleP : public ShapeBase {
   //    Vec3s new_c(c + value * Vec3s(-CA + BC).normalized());
   //
   //    return std::make_pair(new TriangleP(new_a, new_b, new_c),
-  //    Transform3f());
+  //    Transform3s());
   //  }
   //
   //  CoalScalar minInflationValue() const
@@ -212,14 +212,14 @@ class COAL_DLLAPI Box : public ShapeBase {
   ///
   /// \returns a new inflated box and the related transform to account for the
   /// change of shape frame
-  std::pair<Box, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Box, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value << ") "
                                   << "is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
     return std::make_pair(Box(2 * (halfSide + Vec3s::Constant(value))),
-                          Transform3f());
+                          Transform3s());
   }
 
  private:
@@ -278,13 +278,13 @@ class COAL_DLLAPI Sphere : public ShapeBase {
   ///
   /// \returns a new inflated sphere and the related transform to account for
   /// the change of shape frame
-  std::pair<Sphere, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Sphere, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
-    return std::make_pair(Sphere(radius + value), Transform3f());
+    return std::make_pair(Sphere(radius + value), Transform3s());
   }
 
  private:
@@ -352,14 +352,14 @@ class COAL_DLLAPI Ellipsoid : public ShapeBase {
   ///
   /// \returns a new inflated ellipsoid and the related transform to account for
   /// the change of shape frame
-  std::pair<Ellipsoid, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Ellipsoid, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
     return std::make_pair(Ellipsoid(radii + Vec3s::Constant(value)),
-                          Transform3f());
+                          Transform3s());
   }
 
  private:
@@ -437,14 +437,14 @@ class COAL_DLLAPI Capsule : public ShapeBase {
   ///
   /// \returns a new inflated capsule and the related transform to account for
   /// the change of shape frame
-  std::pair<Capsule, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Capsule, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
     return std::make_pair(Capsule(radius + value, 2 * halfLength),
-                          Transform3f());
+                          Transform3s());
   }
 
  private:
@@ -519,7 +519,7 @@ class COAL_DLLAPI Cone : public ShapeBase {
   ///
   /// \returns a new inflated cone and the related transform to account for the
   /// change of shape frame
-  std::pair<Cone, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Cone, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
@@ -538,7 +538,7 @@ class COAL_DLLAPI Cone : public ShapeBase {
     const CoalScalar new_radius = new_lz / tan_alpha;
 
     return std::make_pair(Cone(new_radius, new_lz),
-                          Transform3f(Vec3s(0., 0., new_cz)));
+                          Transform3s(Vec3s(0., 0., new_cz)));
   }
 
  private:
@@ -616,14 +616,14 @@ class COAL_DLLAPI Cylinder : public ShapeBase {
   ///
   /// \returns a new inflated cylinder and the related transform to account for
   /// the change of shape frame
-  std::pair<Cylinder, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Cylinder, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
     return std::make_pair(Cylinder(radius + value, 2 * (halfLength + value)),
-                          Transform3f());
+                          Transform3s());
   }
 
  private:
@@ -943,13 +943,13 @@ class COAL_DLLAPI Halfspace : public ShapeBase {
   ///
   /// \returns a new inflated halfspace and the related transform to account for
   /// the change of shape frame
-  std::pair<Halfspace, Transform3f> inflated(const CoalScalar value) const {
+  std::pair<Halfspace, Transform3s> inflated(const CoalScalar value) const {
     if (value <= minInflationValue())
       COAL_THROW_PRETTY("value (" << value
                                   << ") is two small. It should be at least: "
                                   << minInflationValue(),
                         std::invalid_argument);
-    return std::make_pair(Halfspace(n, d + value), Transform3f());
+    return std::make_pair(Halfspace(n, d + value), Transform3s());
   }
 
   /// @brief Plane normal
diff --git a/include/coal/shape/geometric_shapes_utility.h b/include/coal/shape/geometric_shapes_utility.h
index 30500887065b06695029945e533a322c1958eed5..76ac78ae85ae4a3038d3f6f6923801f7a5ab86a5 100644
--- a/include/coal/shape/geometric_shapes_utility.h
+++ b/include/coal/shape/geometric_shapes_utility.h
@@ -50,27 +50,27 @@ namespace details {
 /// @brief get the vertices of some convex shape which can bound the given shape
 /// in a specific configuration
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Box& box,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Sphere& sphere,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Ellipsoid& ellipsoid,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Capsule& capsule,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Cone& cone,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const Cylinder& cylinder,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const ConvexBase& convex,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 COAL_DLLAPI std::vector<Vec3s> getBoundVertices(const TriangleP& triangle,
-                                                const Transform3f& tf);
+                                                const Transform3s& tf);
 }  // namespace details
 /// @endcond
 
 /// @brief calculate a bounding volume for a shape in a specific configuration
 template <typename BV, typename S>
-inline void computeBV(const S& s, const Transform3f& tf, BV& bv) {
+inline void computeBV(const S& s, const Transform3s& tf, BV& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -81,180 +81,180 @@ inline void computeBV(const S& s, const Transform3f& tf, BV& bv) {
 }
 
 template <>
-COAL_DLLAPI void computeBV<AABB, Box>(const Box& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<AABB, Box>(const Box& s, const Transform3s& tf,
                                       AABB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<AABB, Sphere>(const Sphere& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<AABB, Sphere>(const Sphere& s, const Transform3s& tf,
                                          AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, Ellipsoid>(const Ellipsoid& e,
-                                            const Transform3f& tf, AABB& bv);
+                                            const Transform3s& tf, AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, Capsule>(const Capsule& s,
-                                          const Transform3f& tf, AABB& bv);
+                                          const Transform3s& tf, AABB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<AABB, Cone>(const Cone& s, const Transform3s& tf,
                                        AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, Cylinder>(const Cylinder& s,
-                                           const Transform3f& tf, AABB& bv);
+                                           const Transform3s& tf, AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, ConvexBase>(const ConvexBase& s,
-                                             const Transform3f& tf, AABB& bv);
+                                             const Transform3s& tf, AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, TriangleP>(const TriangleP& s,
-                                            const Transform3f& tf, AABB& bv);
+                                            const Transform3s& tf, AABB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<AABB, Halfspace>(const Halfspace& s,
-                                            const Transform3f& tf, AABB& bv);
+                                            const Transform3s& tf, AABB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<AABB, Plane>(const Plane& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<AABB, Plane>(const Plane& s, const Transform3s& tf,
                                         AABB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<OBB, Box>(const Box& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<OBB, Box>(const Box& s, const Transform3s& tf,
                                      OBB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<OBB, Sphere>(const Sphere& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<OBB, Sphere>(const Sphere& s, const Transform3s& tf,
                                         OBB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<OBB, Capsule>(const Capsule& s,
-                                         const Transform3f& tf, OBB& bv);
+                                         const Transform3s& tf, OBB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<OBB, Cone>(const Cone& s, const Transform3s& tf,
                                       OBB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<OBB, Cylinder>(const Cylinder& s,
-                                          const Transform3f& tf, OBB& bv);
+                                          const Transform3s& tf, OBB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<OBB, ConvexBase>(const ConvexBase& s,
-                                            const Transform3f& tf, OBB& bv);
+                                            const Transform3s& tf, OBB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<OBB, Halfspace>(const Halfspace& s,
-                                           const Transform3f& tf, OBB& bv);
+                                           const Transform3s& tf, OBB& bv);
 
 template <>
 COAL_DLLAPI void computeBV<RSS, Halfspace>(const Halfspace& s,
-                                           const Transform3f& tf, RSS& bv);
+                                           const Transform3s& tf, RSS& bv);
 
 template <>
 COAL_DLLAPI void computeBV<OBBRSS, Halfspace>(const Halfspace& s,
-                                              const Transform3f& tf,
+                                              const Transform3s& tf,
                                               OBBRSS& bv);
 
 template <>
 COAL_DLLAPI void computeBV<kIOS, Halfspace>(const Halfspace& s,
-                                            const Transform3f& tf, kIOS& bv);
+                                            const Transform3s& tf, kIOS& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<16>, Halfspace>(const Halfspace& s,
-                                                const Transform3f& tf,
+                                                const Transform3s& tf,
                                                 KDOP<16>& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<18>, Halfspace>(const Halfspace& s,
-                                                const Transform3f& tf,
+                                                const Transform3s& tf,
                                                 KDOP<18>& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<24>, Halfspace>(const Halfspace& s,
-                                                const Transform3f& tf,
+                                                const Transform3s& tf,
                                                 KDOP<24>& bv);
 
 template <>
-COAL_DLLAPI void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<OBB, Plane>(const Plane& s, const Transform3s& tf,
                                        OBB& bv);
 
 template <>
-COAL_DLLAPI void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<RSS, Plane>(const Plane& s, const Transform3s& tf,
                                        RSS& bv);
 
 template <>
-COAL_DLLAPI void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3s& tf,
                                           OBBRSS& bv);
 
 template <>
-COAL_DLLAPI void computeBV<kIOS, Plane>(const Plane& s, const Transform3f& tf,
+COAL_DLLAPI void computeBV<kIOS, Plane>(const Plane& s, const Transform3s& tf,
                                         kIOS& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<16>, Plane>(const Plane& s,
-                                            const Transform3f& tf,
+                                            const Transform3s& tf,
                                             KDOP<16>& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<18>, Plane>(const Plane& s,
-                                            const Transform3f& tf,
+                                            const Transform3s& tf,
                                             KDOP<18>& bv);
 
 template <>
 COAL_DLLAPI void computeBV<KDOP<24>, Plane>(const Plane& s,
-                                            const Transform3f& tf,
+                                            const Transform3s& tf,
                                             KDOP<24>& bv);
 
 /// @brief construct a box shape (with a configuration) from a given bounding
 /// volume
-COAL_DLLAPI void constructBox(const AABB& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const AABB& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const OBB& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const OBB& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const OBBRSS& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const kIOS& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const kIOS& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const RSS& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const RSS& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<16>& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<18>& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<24>& bv, Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const AABB& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const AABB& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const OBB& bv, const Transform3f& tf_bv, Box& box,
-                              Transform3f& tf);
+COAL_DLLAPI void constructBox(const OBB& bv, const Transform3s& tf_bv, Box& box,
+                              Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const OBBRSS& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const OBBRSS& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const kIOS& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const kIOS& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const RSS& bv, const Transform3f& tf_bv, Box& box,
-                              Transform3f& tf);
+COAL_DLLAPI void constructBox(const RSS& bv, const Transform3s& tf_bv, Box& box,
+                              Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<16>& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<18>& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv,
-                              Box& box, Transform3f& tf);
+COAL_DLLAPI void constructBox(const KDOP<24>& bv, const Transform3s& tf_bv,
+                              Box& box, Transform3s& tf);
 
-COAL_DLLAPI Halfspace transform(const Halfspace& a, const Transform3f& tf);
+COAL_DLLAPI Halfspace transform(const Halfspace& a, const Transform3s& tf);
 
-COAL_DLLAPI Plane transform(const Plane& a, const Transform3f& tf);
+COAL_DLLAPI Plane transform(const Plane& a, const Transform3s& tf);
 
 COAL_DLLAPI std::array<Halfspace, 2> transformToHalfspaces(
-    const Plane& a, const Transform3f& tf);
+    const Plane& a, const Transform3s& tf);
 
 }  // namespace coal
 
diff --git a/python/collision-geometries.cc b/python/collision-geometries.cc
index 63d160bbef8d74e2b236be913e61c5b70a2b7753..fe841d893c514284572135c3157aade017be2374 100644
--- a/python/collision-geometries.cc
+++ b/python/collision-geometries.cc
@@ -699,7 +699,7 @@ void exposeCollisionObject() {
         .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
                       bp::optional<bool>>())
         .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
-                      const Transform3f&, bp::optional<bool>>())
+                      const Transform3s&, bp::optional<bool>>())
         .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
                       const Matrix3s&, const Vec3s&, bp::optional<bool>>())
 
@@ -721,7 +721,7 @@ void exposeCollisionObject() {
                          bp::return_value_policy<bp::copy_const_reference>())
         .def(dv::member_func(
             "setTransform",
-            static_cast<void (CollisionObject::*)(const Transform3f&)>(
+            static_cast<void (CollisionObject::*)(const Transform3s&)>(
                 &CollisionObject::setTransform)))
 
         .DEF_CLASS_FUNC(CollisionObject, isIdentityTransform)
diff --git a/python/collision.cc b/python/collision.cc
index 12e596a102337282c7a6fa34ce079d4a72cf10b9..2c92ad083ef05d6c51e331fa3ee650a761454a09 100644
--- a/python/collision.cc
+++ b/python/collision.cc
@@ -260,8 +260,8 @@ void exposeCollisionAPI() {
                    const CollisionRequest&, CollisionResult&)>(&collide));
   doxygen::def(
       "collide",
-      static_cast<std::size_t (*)(const CollisionGeometry*, const Transform3f&,
-                                  const CollisionGeometry*, const Transform3f&,
+      static_cast<std::size_t (*)(const CollisionGeometry*, const Transform3s&,
+                                  const CollisionGeometry*, const Transform3s&,
                                   const CollisionRequest&, CollisionResult&)>(
           &collide));
 
@@ -271,6 +271,6 @@ void exposeCollisionAPI() {
                     const CollisionGeometry*>())
       .def("__call__",
            static_cast<std::size_t (ComputeCollision::*)(
-               const Transform3f&, const Transform3f&, const CollisionRequest&,
+               const Transform3s&, const Transform3s&, const CollisionRequest&,
                CollisionResult&) const>(&ComputeCollision::operator()));
 }
diff --git a/python/contact_patch.cc b/python/contact_patch.cc
index 4721e8754eaa27cc80fed91a2a23d42b79a4f646..831137b74dabd36077a33583176d7206508b44a4 100644
--- a/python/contact_patch.cc
+++ b/python/contact_patch.cc
@@ -140,8 +140,8 @@ void exposeContactPatchAPI() {
                            ContactPatchResult&)>(&computeContactPatch));
   doxygen::def(
       "computeContactPatch",
-      static_cast<void (*)(const CollisionGeometry*, const Transform3f&,
-                           const CollisionGeometry*, const Transform3f&,
+      static_cast<void (*)(const CollisionGeometry*, const Transform3s&,
+                           const CollisionGeometry*, const Transform3s&,
                            const CollisionResult&, const ContactPatchRequest&,
                            ContactPatchResult&)>(&computeContactPatch));
 
@@ -154,7 +154,7 @@ void exposeContactPatchAPI() {
                       const CollisionGeometry*>())
         .def("__call__",
              static_cast<void (ComputeContactPatch::*)(
-                 const Transform3f&, const Transform3f&, const CollisionResult&,
+                 const Transform3s&, const Transform3s&, const CollisionResult&,
                  const ContactPatchRequest&, ContactPatchResult&) const>(
                  &ComputeContactPatch::operator()));
   }
diff --git a/python/distance.cc b/python/distance.cc
index d83df0143bbc0b22d8128f0365da046415de23cb..1251428bb753258864180d64fda6f94737dd8540 100644
--- a/python/distance.cc
+++ b/python/distance.cc
@@ -154,8 +154,8 @@ void exposeDistanceAPI() {
           &distance));
   doxygen::def(
       "distance",
-      static_cast<CoalScalar (*)(const CollisionGeometry*, const Transform3f&,
-                                 const CollisionGeometry*, const Transform3f&,
+      static_cast<CoalScalar (*)(const CollisionGeometry*, const Transform3s&,
+                                 const CollisionGeometry*, const Transform3s&,
                                  const DistanceRequest&, DistanceResult&)>(
           &distance));
 
@@ -165,6 +165,6 @@ void exposeDistanceAPI() {
                     const CollisionGeometry*>())
       .def("__call__",
            static_cast<CoalScalar (ComputeDistance::*)(
-               const Transform3f&, const Transform3f&, const DistanceRequest&,
+               const Transform3s&, const Transform3s&, const DistanceRequest&,
                DistanceResult&) const>(&ComputeDistance::operator()));
 }
diff --git a/python/gjk.cc b/python/gjk.cc
index a098f2b154381c3275bf4a36d747d8d3de5c2b91..cab5ebde1e736f301bb279cff6ce6eb1f216f2cb 100644
--- a/python/gjk.cc
+++ b/python/gjk.cc
@@ -81,8 +81,8 @@ struct MinkowskiDiffWrapper {
   }
 
   static void set(MinkowskiDiff& self, const ShapeBase* shape0,
-                  const ShapeBase* shape1, const Transform3f& tf0,
-                  const Transform3f& tf1,
+                  const ShapeBase* shape1, const Transform3s& tf0,
+                  const Transform3s& tf1,
                   bool compute_swept_sphere_supports = false) {
     if (compute_swept_sphere_supports) {
       self.set<SupportOptions::WithSweptSphere>(shape0, shape1, tf0, tf1);
@@ -119,13 +119,13 @@ void exposeGJK() {
 
         .def("set",
              static_cast<void (*)(MinkowskiDiff&, const ShapeBase*,
-                                  const ShapeBase*, const Transform3f&,
-                                  const Transform3f&, bool)>(
+                                  const ShapeBase*, const Transform3s&,
+                                  const Transform3s&, bool)>(
                  &MinkowskiDiffWrapper::set),
              doxygen::member_func_doc(
                  static_cast<void (MinkowskiDiff::*)(
-                     const ShapeBase*, const ShapeBase*, const Transform3f&,
-                     const Transform3f&)>(
+                     const ShapeBase*, const ShapeBase*, const Transform3s&,
+                     const Transform3s&)>(
                      &MinkowskiDiff::set<SupportOptions::NoSweptSphere>)))
 
         .def("support0", &MinkowskiDiffWrapper::support0,
diff --git a/python/math.cc b/python/math.cc
index 119d29e04e1a7015e11b2d148a8a7ad688a15d89..be6d13dc490ef2be5085668f370b4caf25837699 100644
--- a/python/math.cc
+++ b/python/math.cc
@@ -77,53 +77,53 @@ void exposeMaths() {
   eigenpy::enableEigenPySpecific<Matrix3s>();
   eigenpy::enableEigenPySpecific<Vec3s>();
 
-  class_<Transform3f>("Transform3f", doxygen::class_doc<Transform3f>(), no_init)
-      .def(dv::init<Transform3f>())
-      .def(dv::init<Transform3f, const Matrix3s::MatrixBase&,
+  class_<Transform3s>("Transform3s", doxygen::class_doc<Transform3s>(), no_init)
+      .def(dv::init<Transform3s>())
+      .def(dv::init<Transform3s, const Matrix3s::MatrixBase&,
                     const Vec3s::MatrixBase&>())
-      .def(dv::init<Transform3f, const Quatf&, const Vec3s::MatrixBase&>())
-      .def(dv::init<Transform3f, const Matrix3s&>())
-      .def(dv::init<Transform3f, const Quatf&>())
-      .def(dv::init<Transform3f, const Vec3s&>())
-      .def(dv::init<Transform3f, const Transform3f&>())
-
-      .def(dv::member_func("getQuatRotation", &Transform3f::getQuatRotation))
-      .def("getTranslation", &Transform3f::getTranslation,
-           doxygen::member_func_doc(&Transform3f::getTranslation),
+      .def(dv::init<Transform3s, const Quatf&, const Vec3s::MatrixBase&>())
+      .def(dv::init<Transform3s, const Matrix3s&>())
+      .def(dv::init<Transform3s, const Quatf&>())
+      .def(dv::init<Transform3s, const Vec3s&>())
+      .def(dv::init<Transform3s, const Transform3s&>())
+
+      .def(dv::member_func("getQuatRotation", &Transform3s::getQuatRotation))
+      .def("getTranslation", &Transform3s::getTranslation,
+           doxygen::member_func_doc(&Transform3s::getTranslation),
            return_value_policy<copy_const_reference>())
-      .def("getRotation", &Transform3f::getRotation,
+      .def("getRotation", &Transform3s::getRotation,
            return_value_policy<copy_const_reference>())
-      .def("isIdentity", &Transform3f::isIdentity,
+      .def("isIdentity", &Transform3s::isIdentity,
            (bp::arg("self"),
             bp::arg("prec") = Eigen::NumTraits<CoalScalar>::dummy_precision()),
-           doxygen::member_func_doc(&Transform3f::getTranslation))
+           doxygen::member_func_doc(&Transform3s::getTranslation))
 
-      .def(dv::member_func("setQuatRotation", &Transform3f::setQuatRotation))
-      .def("setTranslation", &Transform3f::setTranslation<Vec3s>)
-      .def("setRotation", &Transform3f::setRotation<Matrix3s>)
+      .def(dv::member_func("setQuatRotation", &Transform3s::setQuatRotation))
+      .def("setTranslation", &Transform3s::setTranslation<Vec3s>)
+      .def("setRotation", &Transform3s::setRotation<Matrix3s>)
       .def(dv::member_func("setTransform",
-                           &Transform3f::setTransform<Matrix3s, Vec3s>))
+                           &Transform3s::setTransform<Matrix3s, Vec3s>))
       .def(dv::member_func(
           "setTransform",
-          static_cast<void (Transform3f::*)(const Quatf&, const Vec3s&)>(
-              &Transform3f::setTransform)))
-      .def(dv::member_func("setIdentity", &Transform3f::setIdentity))
-      .def(dv::member_func("Identity", &Transform3f::Identity))
+          static_cast<void (Transform3s::*)(const Quatf&, const Vec3s&)>(
+              &Transform3s::setTransform)))
+      .def(dv::member_func("setIdentity", &Transform3s::setIdentity))
+      .def(dv::member_func("Identity", &Transform3s::Identity))
       .staticmethod("Identity")
 
-      .def(dv::member_func("transform", &Transform3f::transform<Vec3s>))
-      .def("inverseInPlace", &Transform3f::inverseInPlace,
+      .def(dv::member_func("transform", &Transform3s::transform<Vec3s>))
+      .def("inverseInPlace", &Transform3s::inverseInPlace,
            return_internal_reference<>(),
-           doxygen::member_func_doc(&Transform3f::inverseInPlace))
-      .def(dv::member_func("inverse", &Transform3f::inverse))
-      .def(dv::member_func("inverseTimes", &Transform3f::inverseTimes))
+           doxygen::member_func_doc(&Transform3s::inverseInPlace))
+      .def(dv::member_func("inverse", &Transform3s::inverse))
+      .def(dv::member_func("inverseTimes", &Transform3s::inverseTimes))
 
       .def(self * self)
       .def(self *= self)
       .def(self == self)
       .def(self != self)
-      .def_pickle(PickleObject<Transform3f>())
-      .def(SerializableVisitor<Transform3f>());
+      .def_pickle(PickleObject<Transform3s>())
+      .def(SerializableVisitor<Transform3s>());
 
   class_<Triangle>("Triangle", no_init)
       .def(dv::init<Triangle>())
diff --git a/src/BVH/BVH_utility.cpp b/src/BVH/BVH_utility.cpp
index 5ce7c2ccdcac5e3b9f3ef9012aed5e1ff12863b2..d3a74960c0537b52a8df6d82d2fa88c2935695d9 100644
--- a/src/BVH/BVH_utility.cpp
+++ b/src/BVH/BVH_utility.cpp
@@ -44,13 +44,13 @@ namespace coal {
 
 namespace details {
 template <typename BV>
-BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, const Transform3f& pose,
+BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, const Transform3s& pose,
                          const AABB& _aabb) {
   assert(model.getModelType() == BVH_MODEL_TRIANGLES);
   const Matrix3s& q = pose.getRotation();
   AABB aabb = translate(_aabb, -pose.getTranslation());
 
-  Transform3f box_pose;
+  Transform3s box_pose;
   Box box;
   constructBox(_aabb, box, box_pose);
   box_pose = pose.inverseTimes(box_pose);
@@ -89,7 +89,7 @@ BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, const Transform3f& pose,
                                             compute_penetration);
       DistanceResult distanceResult;
       const CoalScalar distance = ShapeShapeDistance<Box, TriangleP>(
-          &box, box_pose, &tri, Transform3f(), &gjk, distanceRequest,
+          &box, box_pose, &tri, Transform3s(), &gjk, distanceRequest,
           distanceResult);
       bool is_collision =
           (distance <= gjk.getDistancePrecision(compute_penetration));
@@ -139,43 +139,43 @@ BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, const Transform3f& pose,
 }  // namespace details
 
 template <>
-BVHModel<OBB>* BVHExtract(const BVHModel<OBB>& model, const Transform3f& pose,
+BVHModel<OBB>* BVHExtract(const BVHModel<OBB>& model, const Transform3s& pose,
                           const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
-BVHModel<AABB>* BVHExtract(const BVHModel<AABB>& model, const Transform3f& pose,
+BVHModel<AABB>* BVHExtract(const BVHModel<AABB>& model, const Transform3s& pose,
                            const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
-BVHModel<RSS>* BVHExtract(const BVHModel<RSS>& model, const Transform3f& pose,
+BVHModel<RSS>* BVHExtract(const BVHModel<RSS>& model, const Transform3s& pose,
                           const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
-BVHModel<kIOS>* BVHExtract(const BVHModel<kIOS>& model, const Transform3f& pose,
+BVHModel<kIOS>* BVHExtract(const BVHModel<kIOS>& model, const Transform3s& pose,
                            const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
 BVHModel<OBBRSS>* BVHExtract(const BVHModel<OBBRSS>& model,
-                             const Transform3f& pose, const AABB& aabb) {
+                             const Transform3s& pose, const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
 BVHModel<KDOP<16> >* BVHExtract(const BVHModel<KDOP<16> >& model,
-                                const Transform3f& pose, const AABB& aabb) {
+                                const Transform3s& pose, const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
 BVHModel<KDOP<18> >* BVHExtract(const BVHModel<KDOP<18> >& model,
-                                const Transform3f& pose, const AABB& aabb) {
+                                const Transform3s& pose, const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 template <>
 BVHModel<KDOP<24> >* BVHExtract(const BVHModel<KDOP<24> >& model,
-                                const Transform3f& pose, const AABB& aabb) {
+                                const Transform3s& pose, const AABB& aabb) {
   return details::BVHExtract(model, pose, aabb);
 }
 
diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
index 05ac31513d32e84dcc87cbbdb603b9277c07f433..755d2763face485f2bb6c038e93ae836c132b31f 100644
--- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp
+++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
@@ -55,7 +55,7 @@ namespace dynamic_AABB_tree {
 //==============================================================================
 bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
                        const OcTree* tree2, const OcTree::OcTreeNode* root2,
-                       const AABB& root2_bv, const Transform3f& tf2,
+                       const AABB& root2_bv, const Transform3s& tf2,
                        CollisionCallBackBase* callback) {
   if (!root2) {
     if (root1->isLeaf()) {
@@ -63,12 +63,12 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
 
       if (!obj1->collisionGeometry()->isFree()) {
         OBB obb1, obb2;
-        convertBV(root1->bv, Transform3f::Identity(), obb1);
+        convertBV(root1->bv, Transform3s::Identity(), obb1);
         convertBV(root2_bv, tf2, obb2);
 
         if (obb1.overlap(obb2)) {
           Box* box = new Box();
-          Transform3f box_tf;
+          Transform3s box_tf;
           constructBox(root2_bv, tf2, *box, box_tf);
 
           box->cost_density = tree2->getDefaultOccupancy();
@@ -92,12 +92,12 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
 
     if (!tree2->isNodeFree(root2) && !obj1->collisionGeometry()->isFree()) {
       OBB obb1, obb2;
-      convertBV(root1->bv, Transform3f::Identity(), obb1);
+      convertBV(root1->bv, Transform3s::Identity(), obb1);
       convertBV(root2_bv, tf2, obb2);
 
       if (obb1.overlap(obb2)) {
         Box* box = new Box();
-        Transform3f box_tf;
+        Transform3s box_tf;
         constructBox(root2_bv, tf2, *box, box_tf);
 
         box->cost_density = root2->getOccupancy();
@@ -112,7 +112,7 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
   }
 
   OBB obb1, obb2;
-  convertBV(root1->bv, Transform3f::Identity(), obb1);
+  convertBV(root1->bv, Transform3s::Identity(), obb1);
   convertBV(root2_bv, tf2, obb2);
 
   if (tree2->isNodeFree(root2) || !obb1.overlap(obb2)) return false;
@@ -148,12 +148,12 @@ bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
 //==============================================================================
 bool distanceRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
                       const OcTree* tree2, const OcTree::OcTreeNode* root2,
-                      const AABB& root2_bv, const Transform3f& tf2,
+                      const AABB& root2_bv, const Transform3s& tf2,
                       DistanceCallBackBase* callback, CoalScalar& min_dist) {
   if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
     if (tree2->isNodeOccupied(root2)) {
       Box* box = new Box();
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(root2_bv, tf2, *box, box_tf);
       CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
       return (*callback)(static_cast<CollisionObject*>(root1->data), &obj,
@@ -223,7 +223,7 @@ bool distanceRecurse_(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
 //==============================================================================
 bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
                       const OcTree* tree2, const OcTree::OcTreeNode* root2,
-                      const AABB& root2_bv, const Transform3f& tf2,
+                      const AABB& root2_bv, const Transform3s& tf2,
                       CollisionCallBackBase* callback) {
   if (tf2.rotation().isIdentity())
     return collisionRecurse_(root1, tree2, root2, root2_bv, tf2.translation(),
@@ -235,7 +235,7 @@ bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
 //==============================================================================
 bool distanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode* root1,
                      const OcTree* tree2, const OcTree::OcTreeNode* root2,
-                     const AABB& root2_bv, const Transform3f& tf2,
+                     const AABB& root2_bv, const Transform3s& tf2,
                      DistanceCallBackBase* callback, CoalScalar& min_dist) {
   if (tf2.rotation().isIdentity())
     return distanceRecurse_(root1, tree2, root2, root2_bv, tf2.translation(),
diff --git a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
index 95f440c650b0602f0284ffda2e0749afb586dc8c..9306fa8eb1e03dfb4b975c84eaca8a0cab4bf692 100644
--- a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
+++ b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
@@ -50,7 +50,7 @@ namespace dynamic_AABB_tree_array {
 bool collisionRecurse_(
     DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* nodes1,
     size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
-    const AABB& root2_bv, const Transform3f& tf2,
+    const AABB& root2_bv, const Transform3s& tf2,
     CollisionCallBackBase* callback) {
   DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* root1 =
       nodes1 + root1_id;
@@ -60,12 +60,12 @@ bool collisionRecurse_(
 
       if (!obj1->collisionGeometry()->isFree()) {
         OBB obb1, obb2;
-        convertBV(root1->bv, Transform3f::Identity(), obb1);
+        convertBV(root1->bv, Transform3s::Identity(), obb1);
         convertBV(root2_bv, tf2, obb2);
 
         if (obb1.overlap(obb2)) {
           Box* box = new Box();
-          Transform3f box_tf;
+          Transform3s box_tf;
           constructBox(root2_bv, tf2, *box, box_tf);
 
           box->cost_density = tree2->getDefaultOccupancy();
@@ -88,12 +88,12 @@ bool collisionRecurse_(
     CollisionObject* obj1 = static_cast<CollisionObject*>(root1->data);
     if (!tree2->isNodeFree(root2) && !obj1->collisionGeometry()->isFree()) {
       OBB obb1, obb2;
-      convertBV(root1->bv, Transform3f::Identity(), obb1);
+      convertBV(root1->bv, Transform3s::Identity(), obb1);
       convertBV(root2_bv, tf2, obb2);
 
       if (obb1.overlap(obb2)) {
         Box* box = new Box();
-        Transform3f box_tf;
+        Transform3s box_tf;
         constructBox(root2_bv, tf2, *box, box_tf);
 
         box->cost_density = root2->getOccupancy();
@@ -108,7 +108,7 @@ bool collisionRecurse_(
   }
 
   OBB obb1, obb2;
-  convertBV(root1->bv, Transform3f::Identity(), obb1);
+  convertBV(root1->bv, Transform3s::Identity(), obb1);
   convertBV(root2_bv, tf2, obb2);
 
   if (tree2->isNodeFree(root2) || !obb1.overlap(obb2)) return false;
@@ -148,14 +148,14 @@ bool collisionRecurse_(
 bool distanceRecurse_(
     DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* nodes1,
     size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
-    const AABB& root2_bv, const Transform3f& tf2,
+    const AABB& root2_bv, const Transform3s& tf2,
     DistanceCallBackBase* callback, CoalScalar& min_dist) {
   DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* root1 =
       nodes1 + root1_id;
   if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
     if (tree2->isNodeOccupied(root2)) {
       Box* box = new Box();
-      Transform3f box_tf;
+      Transform3s box_tf;
       constructBox(root2_bv, tf2, *box, box_tf);
       CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
       return (*callback)(static_cast<CollisionObject*>(root1->data), &obj,
@@ -447,7 +447,7 @@ bool selfDistanceRecurse(
 bool collisionRecurse(
     DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* nodes1,
     size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
-    const AABB& root2_bv, const Transform3f& tf2,
+    const AABB& root2_bv, const Transform3s& tf2,
     CollisionCallBackBase* callback) {
   if (tf2.rotation().isIdentity())
     return collisionRecurse_(nodes1, root1_id, tree2, root2, root2_bv,
@@ -461,7 +461,7 @@ bool collisionRecurse(
 bool distanceRecurse(
     DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* nodes1,
     size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
-    const AABB& root2_bv, const Transform3f& tf2,
+    const AABB& root2_bv, const Transform3s& tf2,
     DistanceCallBackBase* callback, CoalScalar& min_dist) {
   if (tf2.rotation().isIdentity())
     return distanceRecurse_(nodes1, root1_id, tree2, root2, root2_bv,
diff --git a/src/collision.cpp b/src/collision.cpp
index 57b923045594b4367efc88dad5f414eb194486e9..95085f3be85b523992d62b2090137b89c4f8653f 100644
--- a/src/collision.cpp
+++ b/src/collision.cpp
@@ -65,8 +65,8 @@ std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
                  result);
 }
 
-std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
-                    const CollisionGeometry* o2, const Transform3f& tf2,
+std::size_t collide(const CollisionGeometry* o1, const Transform3s& tf1,
+                    const CollisionGeometry* o2, const Transform3s& tf2,
                     const CollisionRequest& request, CollisionResult& result) {
   // If security margin is set to -infinity, return that there is no collision
   if (request.security_margin == -std::numeric_limits<CoalScalar>::infinity()) {
@@ -156,8 +156,8 @@ ComputeCollision::ComputeCollision(const CollisionGeometry* o1,
     func = looktable.collision_matrix[node_type1][node_type2];
 }
 
-std::size_t ComputeCollision::run(const Transform3f& tf1,
-                                  const Transform3f& tf2,
+std::size_t ComputeCollision::run(const Transform3s& tf1,
+                                  const Transform3s& tf2,
                                   const CollisionRequest& request,
                                   CollisionResult& result) const {
   // If security margin is set to -infinity, return that there is no collision
@@ -183,8 +183,8 @@ std::size_t ComputeCollision::run(const Transform3f& tf1,
   return res;
 }
 
-std::size_t ComputeCollision::operator()(const Transform3f& tf1,
-                                         const Transform3f& tf2,
+std::size_t ComputeCollision::operator()(const Transform3s& tf1,
+                                         const Transform3s& tf2,
                                          const CollisionRequest& request,
                                          CollisionResult& result) const
 
diff --git a/src/collision_func_matrix.cpp b/src/collision_func_matrix.cpp
index 030711cb6359dbd7a5cc2aba134c26b47d3fd616..e30a2c510d8cd5598dde270dfdb909aaca3ff499 100644
--- a/src/collision_func_matrix.cpp
+++ b/src/collision_func_matrix.cpp
@@ -49,8 +49,8 @@ namespace coal {
 #ifdef COAL_HAS_OCTOMAP
 
 template <typename TypeA, typename TypeB>
-std::size_t OctreeCollide(const CollisionGeometry* o1, const Transform3f& tf1,
-                          const CollisionGeometry* o2, const Transform3f& tf2,
+std::size_t OctreeCollide(const CollisionGeometry* o1, const Transform3s& tf1,
+                          const CollisionGeometry* o2, const Transform3s& tf2,
                           const GJKSolver* nsolver,
                           const CollisionRequest& request,
                           CollisionResult& result) {
@@ -99,9 +99,9 @@ template <typename T_BVH, typename T_SH,
           int _Options = details::bvh_shape_traits<T_BVH, T_SH>::Options>
 struct COAL_LOCAL BVHShapeCollider {
   static std::size_t collide(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const CollisionRequest& request,
                              CollisionResult& result) {
     if (request.isSatisfied(result)) return result.numContacts();
@@ -118,9 +118,9 @@ struct COAL_LOCAL BVHShapeCollider {
   }
 
   static std::size_t aligned(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const CollisionRequest& request,
                              CollisionResult& result) {
     if (request.isSatisfied(result)) return result.numContacts();
@@ -130,7 +130,7 @@ struct COAL_LOCAL BVHShapeCollider {
         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;
+    Transform3s tf1_tmp = tf1;
     const T_SH* obj2 = static_cast<const T_SH*>(o2);
 
     initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, result);
@@ -141,9 +141,9 @@ struct COAL_LOCAL BVHShapeCollider {
   }
 
   static std::size_t oriented(const CollisionGeometry* o1,
-                              const Transform3f& tf1,
+                              const Transform3s& tf1,
                               const CollisionGeometry* o2,
-                              const Transform3f& tf2, const GJKSolver* nsolver,
+                              const Transform3s& tf2, const GJKSolver* nsolver,
                               const CollisionRequest& request,
                               CollisionResult& result) {
     if (request.isSatisfied(result)) return result.numContacts();
@@ -168,9 +168,9 @@ struct COAL_LOCAL HeightFieldShapeCollider {
   typedef HeightField<BV> HF;
 
   static std::size_t collide(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const CollisionRequest& request,
                              CollisionResult& result) {
     if (request.isSatisfied(result)) return result.numContacts();
@@ -189,9 +189,9 @@ struct COAL_LOCAL HeightFieldShapeCollider {
 namespace details {
 template <typename OrientedMeshCollisionTraversalNode, typename T_BVH>
 std::size_t orientedMeshCollide(const CollisionGeometry* o1,
-                                const Transform3f& tf1,
+                                const Transform3s& tf1,
                                 const CollisionGeometry* o2,
-                                const Transform3f& tf2,
+                                const Transform3s& tf2,
                                 const CollisionRequest& request,
                                 CollisionResult& result) {
   if (request.isSatisfied(result)) return result.numContacts();
@@ -209,8 +209,8 @@ std::size_t orientedMeshCollide(const CollisionGeometry* o1,
 }  // namespace details
 
 template <typename T_BVH>
-std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
-                       const CollisionGeometry* o2, const Transform3f& tf2,
+std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3s& tf1,
+                       const CollisionGeometry* o2, const Transform3s& tf2,
                        const CollisionRequest& request,
                        CollisionResult& result) {
   if (request.isSatisfied(result)) return result.numContacts();
@@ -226,9 +226,9 @@ std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
   const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
   const BVHModel<T_BVH>* obj2 = static_cast<const BVHModel<T_BVH>*>(o2);
   BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
-  Transform3f tf1_tmp = tf1;
+  Transform3s tf1_tmp = tf1;
   BVHModel<T_BVH>* obj2_tmp = new BVHModel<T_BVH>(*obj2);
-  Transform3f tf2_tmp = tf2;
+  Transform3s tf2_tmp = tf2;
 
   initialize(node, *obj1_tmp, tf1_tmp, *obj2_tmp, tf2_tmp, result);
   coal::collide(&node, request, result);
@@ -240,8 +240,8 @@ std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
 }
 
 template <>
-std::size_t BVHCollide<OBB>(const CollisionGeometry* o1, const Transform3f& tf1,
-                            const CollisionGeometry* o2, const Transform3f& tf2,
+std::size_t BVHCollide<OBB>(const CollisionGeometry* o1, const Transform3s& tf1,
+                            const CollisionGeometry* o2, const Transform3s& tf2,
                             const CollisionRequest& request,
                             CollisionResult& result) {
   return details::orientedMeshCollide<MeshCollisionTraversalNodeOBB, OBB>(
@@ -250,9 +250,9 @@ std::size_t BVHCollide<OBB>(const CollisionGeometry* o1, const Transform3f& tf1,
 
 template <>
 std::size_t BVHCollide<OBBRSS>(const CollisionGeometry* o1,
-                               const Transform3f& tf1,
+                               const Transform3s& tf1,
                                const CollisionGeometry* o2,
-                               const Transform3f& tf2,
+                               const Transform3s& tf2,
                                const CollisionRequest& request,
                                CollisionResult& result) {
   return details::orientedMeshCollide<MeshCollisionTraversalNodeOBBRSS, OBBRSS>(
@@ -261,9 +261,9 @@ std::size_t BVHCollide<OBBRSS>(const CollisionGeometry* o1,
 
 template <>
 std::size_t BVHCollide<kIOS>(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2,
+                             const Transform3s& tf2,
                              const CollisionRequest& request,
                              CollisionResult& result) {
   return details::orientedMeshCollide<MeshCollisionTraversalNodekIOS, kIOS>(
@@ -271,8 +271,8 @@ std::size_t BVHCollide<kIOS>(const CollisionGeometry* o1,
 }
 
 template <typename T_BVH>
-std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
-                       const CollisionGeometry* o2, const Transform3f& tf2,
+std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3s& tf1,
+                       const CollisionGeometry* o2, const Transform3s& tf2,
                        const GJKSolver* /*nsolver*/,
                        const CollisionRequest& request,
                        CollisionResult& result) {
diff --git a/src/collision_utility.cpp b/src/collision_utility.cpp
index 8fe84680e63851077214c7df7bf29f8006892769..52839d10052313665092142bb6ecf7f6d12589df 100644
--- a/src/collision_utility.cpp
+++ b/src/collision_utility.cpp
@@ -22,7 +22,7 @@ namespace details {
 
 template <typename NT>
 inline CollisionGeometry* extractBVHtpl(const CollisionGeometry* model,
-                                        const Transform3f& pose,
+                                        const Transform3s& pose,
                                         const AABB& aabb) {
   // Ensure AABB is already computed
   if (model->aabb_radius < 0)
@@ -39,7 +39,7 @@ inline CollisionGeometry* extractBVHtpl(const CollisionGeometry* model,
 }
 
 CollisionGeometry* extractBVH(const CollisionGeometry* model,
-                              const Transform3f& pose, const AABB& aabb) {
+                              const Transform3s& pose, const AABB& aabb) {
   switch (model->getNodeType()) {
     case BV_AABB:
       return extractBVHtpl<AABB>(model, pose, aabb);
@@ -64,7 +64,7 @@ CollisionGeometry* extractBVH(const CollisionGeometry* model,
 }  // namespace details
 
 CollisionGeometry* extract(const CollisionGeometry* model,
-                           const Transform3f& pose, const AABB& aabb) {
+                           const Transform3s& pose, const AABB& aabb) {
   switch (model->getObjectType()) {
     case OT_BVH:
       return details::extractBVH(model, pose, aabb);
diff --git a/src/contact_patch.cpp b/src/contact_patch.cpp
index b6e0e1924300f6d8e62d868e0759685d4c68087d..bfc8c7c7d12b78fe2522055980a6a09aa18cb888 100644
--- a/src/contact_patch.cpp
+++ b/src/contact_patch.cpp
@@ -44,8 +44,8 @@ ContactPatchFunctionMatrix& getContactPatchFunctionLookTable() {
   return table;
 }
 
-void computeContactPatch(const CollisionGeometry* o1, const Transform3f& tf1,
-                         const CollisionGeometry* o2, const Transform3f& tf2,
+void computeContactPatch(const CollisionGeometry* o1, const Transform3s& tf1,
+                         const CollisionGeometry* o2, const Transform3s& tf2,
                          const CollisionResult& collision_result,
                          const ContactPatchRequest& request,
                          ContactPatchResult& result) {
@@ -136,7 +136,7 @@ ComputeContactPatch::ComputeContactPatch(const CollisionGeometry* o1,
   }
 }
 
-void ComputeContactPatch::run(const Transform3f& tf1, const Transform3f& tf2,
+void ComputeContactPatch::run(const Transform3s& tf1, const Transform3s& tf2,
                               const CollisionResult& collision_result,
                               const ContactPatchRequest& request,
                               ContactPatchResult& result) const {
@@ -157,8 +157,8 @@ void ComputeContactPatch::run(const Transform3f& tf1, const Transform3f& tf2,
   }
 }
 
-void ComputeContactPatch::operator()(const Transform3f& tf1,
-                                     const Transform3f& tf2,
+void ComputeContactPatch::operator()(const Transform3s& tf1,
+                                     const Transform3s& tf2,
                                      const CollisionResult& collision_result,
                                      const ContactPatchRequest& request,
                                      ContactPatchResult& result) const
diff --git a/src/contact_patch_func_matrix.cpp b/src/contact_patch_func_matrix.cpp
index e20305b3784ee5f880c59284c5a08d0de410b898..aec69f679343239468301f7bc100fe5f4ef18881 100644
--- a/src/contact_patch_func_matrix.cpp
+++ b/src/contact_patch_func_matrix.cpp
@@ -43,8 +43,8 @@ namespace coal {
 
 template <typename T_BVH, typename T_SH>
 struct BVHShapeComputeContactPatch {
-  static void run(const CollisionGeometry* o1, const Transform3f& tf1,
-                  const CollisionGeometry* o2, const Transform3f& tf2,
+  static void run(const CollisionGeometry* o1, const Transform3s& tf1,
+                  const CollisionGeometry* o2, const Transform3s& tf2,
                   const CollisionResult& collision_result,
                   const ContactPatchSolver* csolver,
                   const ContactPatchRequest& request,
@@ -68,8 +68,8 @@ struct BVHShapeComputeContactPatch {
 
 template <typename BV, typename Shape>
 struct HeightFieldShapeComputeContactPatch {
-  static void run(const CollisionGeometry* o1, const Transform3f& tf1,
-                  const CollisionGeometry* o2, const Transform3f& tf2,
+  static void run(const CollisionGeometry* o1, const Transform3s& tf1,
+                  const CollisionGeometry* o2, const Transform3s& tf2,
                   const CollisionResult& collision_result,
                   const ContactPatchSolver* csolver,
                   const ContactPatchRequest& request,
@@ -93,8 +93,8 @@ struct HeightFieldShapeComputeContactPatch {
 
 template <typename BV>
 struct BVHComputeContactPatch {
-  static void run(const CollisionGeometry* o1, const Transform3f& tf1,
-                  const CollisionGeometry* o2, const Transform3f& tf2,
+  static void run(const CollisionGeometry* o1, const Transform3s& tf1,
+                  const CollisionGeometry* o2, const Transform3s& tf2,
                   const CollisionResult& collision_result,
                   const ContactPatchSolver* csolver,
                   const ContactPatchRequest& request,
@@ -117,8 +117,8 @@ struct BVHComputeContactPatch {
 };
 
 COAL_LOCAL void contact_patch_function_not_implemented(
-    const CollisionGeometry* o1, const Transform3f& /*tf1*/,
-    const CollisionGeometry* o2, const Transform3f& /*tf2*/,
+    const CollisionGeometry* o1, const Transform3s& /*tf1*/,
+    const CollisionGeometry* o2, const Transform3s& /*tf2*/,
     const CollisionResult& /*collision_result*/,
     const ContactPatchSolver* /*csolver*/,
     const ContactPatchRequest& /*request*/, ContactPatchResult& /*result*/) {
diff --git a/src/distance.cpp b/src/distance.cpp
index 97dc1f5e5a7095798103b353d3e19a533c3f0ef5..42cc52e09a9ece68d4a3bb812cdf1a944372a47b 100644
--- a/src/distance.cpp
+++ b/src/distance.cpp
@@ -56,8 +56,8 @@ CoalScalar distance(const CollisionObject* o1, const CollisionObject* o2,
                   result);
 }
 
-CoalScalar distance(const CollisionGeometry* o1, const Transform3f& tf1,
-                    const CollisionGeometry* o2, const Transform3f& tf2,
+CoalScalar distance(const CollisionGeometry* o1, const Transform3s& tf1,
+                    const CollisionGeometry* o2, const Transform3s& tf2,
                     const DistanceRequest& request, DistanceResult& result) {
   GJKSolver solver(request);
 
@@ -135,7 +135,7 @@ ComputeDistance::ComputeDistance(const CollisionGeometry* o1,
     func = looktable.distance_matrix[node_type1][node_type2];
 }
 
-CoalScalar ComputeDistance::run(const Transform3f& tf1, const Transform3f& tf2,
+CoalScalar ComputeDistance::run(const Transform3s& tf1, const Transform3s& tf2,
                                 const DistanceRequest& request,
                                 DistanceResult& result) const {
   CoalScalar res;
@@ -156,8 +156,8 @@ CoalScalar ComputeDistance::run(const Transform3f& tf1, const Transform3f& tf2,
   return res;
 }
 
-CoalScalar ComputeDistance::operator()(const Transform3f& tf1,
-                                       const Transform3f& tf2,
+CoalScalar ComputeDistance::operator()(const Transform3s& tf1,
+                                       const Transform3s& tf2,
                                        const DistanceRequest& request,
                                        DistanceResult& result) const {
   solver.set(request);
diff --git a/src/distance/box_halfspace.cpp b/src/distance/box_halfspace.cpp
index 8a4c3a185e499f8b94b2020ff6a924b9aaab83a3..913f626e3f9f0e76344f519935d9105f7210a13e 100644
--- a/src/distance/box_halfspace.cpp
+++ b/src/distance/box_halfspace.cpp
@@ -49,8 +49,8 @@ namespace internal {
 
 template <>
 CoalScalar ShapeShapeDistance<Box, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Box& s1 = static_cast<const Box&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -62,8 +62,8 @@ CoalScalar ShapeShapeDistance<Box, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Box>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Box& s2 = static_cast<const Box&>(*o2);
diff --git a/src/distance/box_plane.cpp b/src/distance/box_plane.cpp
index cdcde09e23c748eaa9c9881811abe194550332a7..b3cb6015e4296455bd6ce3bda5754590a2802f18 100644
--- a/src/distance/box_plane.cpp
+++ b/src/distance/box_plane.cpp
@@ -48,9 +48,9 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Box, Plane>(const CollisionGeometry* o1,
-                                          const Transform3f& tf1,
+                                          const Transform3s& tf1,
                                           const CollisionGeometry* o2,
-                                          const Transform3f& tf2,
+                                          const Transform3s& tf2,
                                           const GJKSolver*, const bool,
                                           Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Box& s1 = static_cast<const Box&>(*o1);
@@ -63,9 +63,9 @@ CoalScalar ShapeShapeDistance<Box, Plane>(const CollisionGeometry* o1,
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Box>(const CollisionGeometry* o1,
-                                          const Transform3f& tf1,
+                                          const Transform3s& tf1,
                                           const CollisionGeometry* o2,
-                                          const Transform3f& tf2,
+                                          const Transform3s& tf2,
                                           const GJKSolver*, const bool,
                                           Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
diff --git a/src/distance/box_sphere.cpp b/src/distance/box_sphere.cpp
index 4c249b40ccc67a95be48ce8f588a39c59d9d39e9..0b6dbfb2499f8eaed32ee8b09338592ecf4764f8 100644
--- a/src/distance/box_sphere.cpp
+++ b/src/distance/box_sphere.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Box, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Box& s1 = static_cast<const Box&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
@@ -58,8 +58,8 @@ CoalScalar ShapeShapeDistance<Box, Sphere>(
 
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Box>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Box& s2 = static_cast<const Box&>(*o2);
diff --git a/src/distance/capsule_capsule.cpp b/src/distance/capsule_capsule.cpp
index ad5a2c05127796ca6aa77806cd2ea85116336f65..0ec5137f6e03cfe60648e934911f0913bbcabe26 100644
--- a/src/distance/capsule_capsule.cpp
+++ b/src/distance/capsule_capsule.cpp
@@ -78,8 +78,8 @@ void clamped_linear(Vec3s& a_sd, const Vec3s& a, const CoalScalar& s_n,
 /// @param normal: normal pointing from capsule1 to capsule2
 template <>
 CoalScalar ShapeShapeDistance<Capsule, Capsule>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& wp1, Vec3s& wp2, Vec3s& normal) {
   const Capsule* capsule1 = static_cast<const Capsule*>(o1);
   const Capsule* capsule2 = static_cast<const Capsule*>(o2);
diff --git a/src/distance/capsule_halfspace.cpp b/src/distance/capsule_halfspace.cpp
index 16b42d259a31aacaeae50310d4ecb46dc151ea90..70c53b918f04fb93354aac47f030f3466758fcbe 100644
--- a/src/distance/capsule_halfspace.cpp
+++ b/src/distance/capsule_halfspace.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Capsule, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Capsule& s1 = static_cast<const Capsule&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Capsule, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Capsule>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Capsule& s2 = static_cast<const Capsule&>(*o2);
diff --git a/src/distance/capsule_plane.cpp b/src/distance/capsule_plane.cpp
index 2d587cfb78d81c34dd06370774efc498999227bc..27fe19778f2b66211b86c25fdeb6ef6a29732c92 100644
--- a/src/distance/capsule_plane.cpp
+++ b/src/distance/capsule_plane.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Capsule, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Capsule& s1 = static_cast<const Capsule&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Capsule, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Capsule>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Capsule& s2 = static_cast<const Capsule&>(*o2);
diff --git a/src/distance/cone_halfspace.cpp b/src/distance/cone_halfspace.cpp
index 10159a989bc86d69173cd1a5faa47660ef4b53fb..38276b539b9a4f4b34c82959418b28da821b0761 100644
--- a/src/distance/cone_halfspace.cpp
+++ b/src/distance/cone_halfspace.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Cone, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Cone& s1 = static_cast<const Cone&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Cone, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Cone>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Cone& s2 = static_cast<const Cone&>(*o2);
diff --git a/src/distance/cone_plane.cpp b/src/distance/cone_plane.cpp
index 9e905bc3653c954e9e02244afaaaa066b72e4865..b26832a965662cdc50ad96d72f5935a35673c4da 100644
--- a/src/distance/cone_plane.cpp
+++ b/src/distance/cone_plane.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Cone, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Cone& s1 = static_cast<const Cone&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Cone, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Cone>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Cone& s2 = static_cast<const Cone&>(*o2);
diff --git a/src/distance/convex_halfspace.cpp b/src/distance/convex_halfspace.cpp
index 274632596b5d3e1d8bae7df10fffc4293c63a553..bda32965d8ef459bc04ef0759bc4824ed795dd00 100644
--- a/src/distance/convex_halfspace.cpp
+++ b/src/distance/convex_halfspace.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<ConvexBase, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const ConvexBase& s1 = static_cast<const ConvexBase&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -57,8 +57,8 @@ CoalScalar ShapeShapeDistance<ConvexBase, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, ConvexBase>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const ConvexBase& s2 = static_cast<const ConvexBase&>(*o2);
diff --git a/src/distance/convex_plane.cpp b/src/distance/convex_plane.cpp
index a4907880d5c53b1487134b5e632567cf7dcf49fa..c89b57c7ff8c5a251d4d02641d78809680f509c6 100644
--- a/src/distance/convex_plane.cpp
+++ b/src/distance/convex_plane.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<ConvexBase, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const ConvexBase& s1 = static_cast<const ConvexBase&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -57,8 +57,8 @@ CoalScalar ShapeShapeDistance<ConvexBase, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, ConvexBase>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const ConvexBase& s2 = static_cast<const ConvexBase&>(*o2);
diff --git a/src/distance/cylinder_halfspace.cpp b/src/distance/cylinder_halfspace.cpp
index bdff1a2ed38b47a5ab86e0badfa5bbb0fbdbacef..c29e6f7ca12e1a53a8f511d9b8f8592b3c14c3e5 100644
--- a/src/distance/cylinder_halfspace.cpp
+++ b/src/distance/cylinder_halfspace.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Cylinder, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Cylinder& s1 = static_cast<const Cylinder&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Cylinder, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Cylinder>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Cylinder& s2 = static_cast<const Cylinder&>(*o2);
diff --git a/src/distance/cylinder_plane.cpp b/src/distance/cylinder_plane.cpp
index 807d3bf9945ee411df81f28a7d563237c70511d3..2d3db927c934e263e36f45216f6cd918430fc866 100644
--- a/src/distance/cylinder_plane.cpp
+++ b/src/distance/cylinder_plane.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Cylinder, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Cylinder& s1 = static_cast<const Cylinder&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Cylinder, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Cylinder>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Cylinder& s2 = static_cast<const Cylinder&>(*o2);
diff --git a/src/distance/ellipsoid_halfspace.cpp b/src/distance/ellipsoid_halfspace.cpp
index 9c2674dc6581740d34ba949ee6daf100f04d2099..d69e3db97899fbfbb7cbbff7c9de783865e7079e 100644
--- a/src/distance/ellipsoid_halfspace.cpp
+++ b/src/distance/ellipsoid_halfspace.cpp
@@ -46,8 +46,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Ellipsoid, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Ellipsoid& s1 = static_cast<const Ellipsoid&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -59,8 +59,8 @@ CoalScalar ShapeShapeDistance<Ellipsoid, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Ellipsoid>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Ellipsoid& s2 = static_cast<const Ellipsoid&>(*o2);
diff --git a/src/distance/ellipsoid_plane.cpp b/src/distance/ellipsoid_plane.cpp
index 4cc31f3aa270ca00ad2022a19199b11484a73f28..eae31b84445595cdf8487a4827ae9a779d7e8837 100644
--- a/src/distance/ellipsoid_plane.cpp
+++ b/src/distance/ellipsoid_plane.cpp
@@ -45,8 +45,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Ellipsoid, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Ellipsoid& s1 = static_cast<const Ellipsoid&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -58,8 +58,8 @@ CoalScalar ShapeShapeDistance<Ellipsoid, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Ellipsoid>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Ellipsoid& s2 = static_cast<const Ellipsoid&>(*o2);
diff --git a/src/distance/halfspace_halfspace.cpp b/src/distance/halfspace_halfspace.cpp
index e1fa824fd5c8274ded549644fda6103ca7a29199..9bad0a5966a9d97a9efd77990b39f40bafaa22af 100644
--- a/src/distance/halfspace_halfspace.cpp
+++ b/src/distance/halfspace_halfspace.cpp
@@ -45,8 +45,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
diff --git a/src/distance/halfspace_plane.cpp b/src/distance/halfspace_plane.cpp
index 7fdf4bf982d965402d408a37bb13505524bc1dbd..b0bd3c079dbb62db0054b44cd802f334ffa77566 100644
--- a/src/distance/halfspace_plane.cpp
+++ b/src/distance/halfspace_plane.cpp
@@ -45,8 +45,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -55,8 +55,8 @@ CoalScalar ShapeShapeDistance<Halfspace, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
diff --git a/src/distance/plane_plane.cpp b/src/distance/plane_plane.cpp
index 5598e92f12ae4181b5105f237a2bf708b53b49dd..b14bb30996dbee7f0b134a64b62e6417ce9d2bc0 100644
--- a/src/distance/plane_plane.cpp
+++ b/src/distance/plane_plane.cpp
@@ -45,8 +45,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Plane, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
diff --git a/src/distance/sphere_capsule.cpp b/src/distance/sphere_capsule.cpp
index b2b79d7aae475918b0d70a6282189d39f7c1a737..719041b6ecde5ca586405007494d5ab02088df65 100644
--- a/src/distance/sphere_capsule.cpp
+++ b/src/distance/sphere_capsule.cpp
@@ -45,8 +45,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Capsule>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Capsule& s2 = static_cast<const Capsule&>(*o2);
@@ -55,8 +55,8 @@ CoalScalar ShapeShapeDistance<Sphere, Capsule>(
 
 template <>
 CoalScalar ShapeShapeDistance<Capsule, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Capsule& s1 = static_cast<const Capsule&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
diff --git a/src/distance/sphere_cylinder.cpp b/src/distance/sphere_cylinder.cpp
index 6844c201f8a13cc52bac932125b3ec51a927ebd4..743989f198b777ef41f5a67c1ab7f8a441e075ab 100644
--- a/src/distance/sphere_cylinder.cpp
+++ b/src/distance/sphere_cylinder.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Cylinder>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Cylinder& s2 = static_cast<const Cylinder&>(*o2);
@@ -58,8 +58,8 @@ CoalScalar ShapeShapeDistance<Sphere, Cylinder>(
 
 template <>
 CoalScalar ShapeShapeDistance<Cylinder, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Cylinder& s1 = static_cast<const Cylinder&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
diff --git a/src/distance/sphere_halfspace.cpp b/src/distance/sphere_halfspace.cpp
index 632836570c86c026da198d00169439b0cf09781f..9a6fbe3054018b9cdd841efe57e268a669a0673e 100644
--- a/src/distance/sphere_halfspace.cpp
+++ b/src/distance/sphere_halfspace.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Sphere, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
diff --git a/src/distance/sphere_plane.cpp b/src/distance/sphere_plane.cpp
index d423786ebe8bcd7a39f3c16b6ed2cf703e49de5e..21438a54995d1c8816cf7bae8ddcfad50c0d6ba5 100644
--- a/src/distance/sphere_plane.cpp
+++ b/src/distance/sphere_plane.cpp
@@ -48,8 +48,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -61,8 +61,8 @@ CoalScalar ShapeShapeDistance<Sphere, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
diff --git a/src/distance/sphere_sphere.cpp b/src/distance/sphere_sphere.cpp
index 6546ab183d63858970e58365922489fa880cc8ce..ac72a8c74c6c40a9eb45d19a0e49fa71282fda0c 100644
--- a/src/distance/sphere_sphere.cpp
+++ b/src/distance/sphere_sphere.cpp
@@ -54,8 +54,8 @@ struct GJKSolver;
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<Sphere, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
diff --git a/src/distance/triangle_halfspace.cpp b/src/distance/triangle_halfspace.cpp
index 8f4b0892d4e7ffec0bf6a1944dd32bcbeff2e5c8..5f4da480722b5feee25b987992537dd13a8006d8 100644
--- a/src/distance/triangle_halfspace.cpp
+++ b/src/distance/triangle_halfspace.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<TriangleP, Halfspace>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const TriangleP& s1 = static_cast<const TriangleP&>(*o1);
   const Halfspace& s2 = static_cast<const Halfspace&>(*o2);
@@ -57,8 +57,8 @@ CoalScalar ShapeShapeDistance<TriangleP, Halfspace>(
 
 template <>
 CoalScalar ShapeShapeDistance<Halfspace, TriangleP>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Halfspace& s1 = static_cast<const Halfspace&>(*o1);
   const TriangleP& s2 = static_cast<const TriangleP&>(*o2);
diff --git a/src/distance/triangle_plane.cpp b/src/distance/triangle_plane.cpp
index 8db569fb8a36597cbbef79435c78bd7eabb69db4..87a90ae5d465c9499b0f54c5b0d221887495a066 100644
--- a/src/distance/triangle_plane.cpp
+++ b/src/distance/triangle_plane.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<TriangleP, Plane>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const TriangleP& s1 = static_cast<const TriangleP&>(*o1);
   const Plane& s2 = static_cast<const Plane&>(*o2);
@@ -57,8 +57,8 @@ CoalScalar ShapeShapeDistance<TriangleP, Plane>(
 
 template <>
 CoalScalar ShapeShapeDistance<Plane, TriangleP>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Plane& s1 = static_cast<const Plane&>(*o1);
   const TriangleP& s2 = static_cast<const TriangleP&>(*o2);
diff --git a/src/distance/triangle_sphere.cpp b/src/distance/triangle_sphere.cpp
index 278e54db3486d502a28c08ff6ead1fa111cb4440..2bcb6beb94e7fa2702eee9ea3d0dff6680c1a5dd 100644
--- a/src/distance/triangle_sphere.cpp
+++ b/src/distance/triangle_sphere.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<TriangleP, Sphere>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const TriangleP& s1 = static_cast<const TriangleP&>(*o1);
   const Sphere& s2 = static_cast<const Sphere&>(*o2);
@@ -57,8 +57,8 @@ CoalScalar ShapeShapeDistance<TriangleP, Sphere>(
 
 template <>
 CoalScalar ShapeShapeDistance<Sphere, TriangleP>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver*,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
     const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const Sphere& s1 = static_cast<const Sphere&>(*o1);
   const TriangleP& s2 = static_cast<const TriangleP&>(*o2);
diff --git a/src/distance/triangle_triangle.cpp b/src/distance/triangle_triangle.cpp
index 9f3166642184da53032f802481bcaccc3aaac8f6..ccbe2b7f9b83cc352fc39c476ed1e2111c57906d 100644
--- a/src/distance/triangle_triangle.cpp
+++ b/src/distance/triangle_triangle.cpp
@@ -44,8 +44,8 @@ namespace coal {
 namespace internal {
 template <>
 CoalScalar ShapeShapeDistance<TriangleP, TriangleP>(
-    const CollisionGeometry* o1, const Transform3f& tf1,
-    const CollisionGeometry* o2, const Transform3f& tf2,
+    const CollisionGeometry* o1, const Transform3s& tf1,
+    const CollisionGeometry* o2, const Transform3s& tf2,
     const GJKSolver* solver, const bool, Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   // Transform the triangles in world frame
   const TriangleP& s1 = static_cast<const TriangleP&>(*o1);
diff --git a/src/distance_func_matrix.cpp b/src/distance_func_matrix.cpp
index 5b482f2989e766c6c5adb5ddba7abe4d07f831fa..fbfeb664050bb1ce607a6d14c9d93e7b8216e103 100644
--- a/src/distance_func_matrix.cpp
+++ b/src/distance_func_matrix.cpp
@@ -48,8 +48,8 @@ namespace coal {
 #ifdef COAL_HAS_OCTOMAP
 
 template <typename TypeA, typename TypeB>
-CoalScalar Distance(const CollisionGeometry* o1, const Transform3f& tf1,
-                    const CollisionGeometry* o2, const Transform3f& tf2,
+CoalScalar Distance(const CollisionGeometry* o1, const Transform3s& tf1,
+                    const CollisionGeometry* o2, const Transform3s& tf2,
                     const GJKSolver* nsolver, const DistanceRequest& request,
                     DistanceResult& result) {
   if (request.isSatisfied(result)) return result.min_distance;
@@ -67,8 +67,8 @@ CoalScalar Distance(const CollisionGeometry* o1, const Transform3f& tf1,
 #endif
 
 COAL_LOCAL CoalScalar distance_function_not_implemented(
-    const CollisionGeometry* o1, const Transform3f& /*tf1*/,
-    const CollisionGeometry* o2, const Transform3f& /*tf2*/,
+    const CollisionGeometry* o1, const Transform3s& /*tf1*/,
+    const CollisionGeometry* o2, const Transform3s& /*tf2*/,
     const GJKSolver* /*nsolver*/, const DistanceRequest& /*request*/,
     DistanceResult& /*result*/) {
   NODE_TYPE node_type1 = o1->getNodeType();
@@ -85,16 +85,16 @@ COAL_LOCAL CoalScalar distance_function_not_implemented(
 template <typename T_BVH, typename T_SH>
 struct COAL_LOCAL BVHShapeDistancer {
   static CoalScalar distance(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const DistanceRequest& request,
                              DistanceResult& result) {
     if (request.isSatisfied(result)) return result.min_distance;
     MeshShapeDistanceTraversalNode<T_BVH, T_SH> node;
     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;
+    Transform3s tf1_tmp = tf1;
     const T_SH* obj2 = static_cast<const T_SH*>(o2);
 
     initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, request, result);
@@ -110,9 +110,9 @@ namespace details {
 template <typename OrientedMeshShapeDistanceTraversalNode, typename T_BVH,
           typename T_SH>
 CoalScalar orientedBVHShapeDistance(const CollisionGeometry* o1,
-                                    const Transform3f& tf1,
+                                    const Transform3s& tf1,
                                     const CollisionGeometry* o2,
-                                    const Transform3f& tf2,
+                                    const Transform3s& tf2,
                                     const GJKSolver* nsolver,
                                     const DistanceRequest& request,
                                     DistanceResult& result) {
@@ -132,9 +132,9 @@ CoalScalar orientedBVHShapeDistance(const CollisionGeometry* o1,
 template <typename T_SH>
 struct COAL_LOCAL BVHShapeDistancer<RSS, T_SH> {
   static CoalScalar distance(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const DistanceRequest& request,
                              DistanceResult& result) {
     return details::orientedBVHShapeDistance<
@@ -146,9 +146,9 @@ struct COAL_LOCAL BVHShapeDistancer<RSS, T_SH> {
 template <typename T_SH>
 struct COAL_LOCAL BVHShapeDistancer<kIOS, T_SH> {
   static CoalScalar distance(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const DistanceRequest& request,
                              DistanceResult& result) {
     return details::orientedBVHShapeDistance<
@@ -160,9 +160,9 @@ struct COAL_LOCAL BVHShapeDistancer<kIOS, T_SH> {
 template <typename T_SH>
 struct COAL_LOCAL BVHShapeDistancer<OBBRSS, T_SH> {
   static CoalScalar distance(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const DistanceRequest& request,
                              DistanceResult& result) {
     return details::orientedBVHShapeDistance<
@@ -174,9 +174,9 @@ struct COAL_LOCAL BVHShapeDistancer<OBBRSS, T_SH> {
 template <typename T_HF, typename T_SH>
 struct COAL_LOCAL HeightFieldShapeDistancer {
   static CoalScalar distance(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2, const GJKSolver* nsolver,
+                             const Transform3s& tf2, const GJKSolver* nsolver,
                              const DistanceRequest& request,
                              DistanceResult& result) {
     COAL_UNUSED_VARIABLE(o1);
@@ -203,17 +203,17 @@ struct COAL_LOCAL HeightFieldShapeDistancer {
 };
 
 template <typename T_BVH>
-CoalScalar BVHDistance(const CollisionGeometry* o1, const Transform3f& tf1,
-                       const CollisionGeometry* o2, const Transform3f& tf2,
+CoalScalar BVHDistance(const CollisionGeometry* o1, const Transform3s& tf1,
+                       const CollisionGeometry* o2, const Transform3s& tf2,
                        const DistanceRequest& request, DistanceResult& result) {
   if (request.isSatisfied(result)) return result.min_distance;
   MeshDistanceTraversalNode<T_BVH> node;
   const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
   const BVHModel<T_BVH>* obj2 = static_cast<const BVHModel<T_BVH>*>(o2);
   BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
-  Transform3f tf1_tmp = tf1;
+  Transform3s tf1_tmp = tf1;
   BVHModel<T_BVH>* obj2_tmp = new BVHModel<T_BVH>(*obj2);
-  Transform3f tf2_tmp = tf2;
+  Transform3s tf2_tmp = tf2;
 
   initialize(node, *obj1_tmp, tf1_tmp, *obj2_tmp, tf2_tmp, request, result);
   distance(&node);
@@ -226,9 +226,9 @@ CoalScalar BVHDistance(const CollisionGeometry* o1, const Transform3f& tf1,
 namespace details {
 template <typename OrientedMeshDistanceTraversalNode, typename T_BVH>
 CoalScalar orientedMeshDistance(const CollisionGeometry* o1,
-                                const Transform3f& tf1,
+                                const Transform3s& tf1,
                                 const CollisionGeometry* o2,
-                                const Transform3f& tf2,
+                                const Transform3s& tf2,
                                 const DistanceRequest& request,
                                 DistanceResult& result) {
   if (request.isSatisfied(result)) return result.min_distance;
@@ -245,8 +245,8 @@ CoalScalar orientedMeshDistance(const CollisionGeometry* o1,
 }  // namespace details
 
 template <>
-CoalScalar BVHDistance<RSS>(const CollisionGeometry* o1, const Transform3f& tf1,
-                            const CollisionGeometry* o2, const Transform3f& tf2,
+CoalScalar BVHDistance<RSS>(const CollisionGeometry* o1, const Transform3s& tf1,
+                            const CollisionGeometry* o2, const Transform3s& tf2,
                             const DistanceRequest& request,
                             DistanceResult& result) {
   return details::orientedMeshDistance<MeshDistanceTraversalNodeRSS, RSS>(
@@ -255,9 +255,9 @@ CoalScalar BVHDistance<RSS>(const CollisionGeometry* o1, const Transform3f& tf1,
 
 template <>
 CoalScalar BVHDistance<kIOS>(const CollisionGeometry* o1,
-                             const Transform3f& tf1,
+                             const Transform3s& tf1,
                              const CollisionGeometry* o2,
-                             const Transform3f& tf2,
+                             const Transform3s& tf2,
                              const DistanceRequest& request,
                              DistanceResult& result) {
   return details::orientedMeshDistance<MeshDistanceTraversalNodekIOS, kIOS>(
@@ -266,9 +266,9 @@ CoalScalar BVHDistance<kIOS>(const CollisionGeometry* o1,
 
 template <>
 CoalScalar BVHDistance<OBBRSS>(const CollisionGeometry* o1,
-                               const Transform3f& tf1,
+                               const Transform3s& tf1,
                                const CollisionGeometry* o2,
-                               const Transform3f& tf2,
+                               const Transform3s& tf2,
                                const DistanceRequest& request,
                                DistanceResult& result) {
   return details::orientedMeshDistance<MeshDistanceTraversalNodeOBBRSS, OBBRSS>(
@@ -276,8 +276,8 @@ CoalScalar BVHDistance<OBBRSS>(const CollisionGeometry* o1,
 }
 
 template <typename T_BVH>
-CoalScalar BVHDistance(const CollisionGeometry* o1, const Transform3f& tf1,
-                       const CollisionGeometry* o2, const Transform3f& tf2,
+CoalScalar BVHDistance(const CollisionGeometry* o1, const Transform3s& tf1,
+                       const CollisionGeometry* o2, const Transform3s& tf2,
                        const GJKSolver* /*nsolver*/,
                        const DistanceRequest& request, DistanceResult& result) {
   return BVHDistance<T_BVH>(o1, tf1, o2, tf2, request, result);
diff --git a/src/intersect.cpp b/src/intersect.cpp
index 6440ab5dafaf982d579546ce8096ce176a3b5fe1..cd1320dd352d9555d22443680b86e80697c50fad 100644
--- a/src/intersect.cpp
+++ b/src/intersect.cpp
@@ -395,7 +395,7 @@ CoalScalar TriangleDistance::sqrTriDistance(const Vec3s S[3], const Vec3s T[3],
 }
 
 CoalScalar TriangleDistance::sqrTriDistance(const Vec3s S[3], const Vec3s T[3],
-                                            const Transform3f& tf, Vec3s& P,
+                                            const Transform3s& tf, Vec3s& P,
                                             Vec3s& Q) {
   Vec3s T_transformed[3];
   T_transformed[0] = tf.transform(T[0]);
@@ -420,7 +420,7 @@ CoalScalar TriangleDistance::sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
 CoalScalar TriangleDistance::sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
                                             const Vec3s& S3, const Vec3s& T1,
                                             const Vec3s& T2, const Vec3s& T3,
-                                            const Transform3f& tf, Vec3s& P,
+                                            const Transform3s& tf, Vec3s& P,
                                             Vec3s& Q) {
   Vec3s T1_transformed = tf.transform(T1);
   Vec3s T2_transformed = tf.transform(T2);
diff --git a/src/math/transform.cpp b/src/math/transform.cpp
index 844c9c183a26e9c7b4bd4118533870e12c675717..502b22ab15835879963eba8548e396f4c9974998 100644
--- a/src/math/transform.cpp
+++ b/src/math/transform.cpp
@@ -39,15 +39,15 @@
 
 namespace coal {
 
-void relativeTransform(const Transform3f& tf1, const Transform3f& tf2,
-                       Transform3f& tf) {
+void relativeTransform(const Transform3s& tf1, const Transform3s& tf2,
+                       Transform3s& tf) {
   tf = tf1.inverseTimes(tf2);
 }
 
-void relativeTransform2(const Transform3f& tf1, const Transform3f& tf2,
-                        Transform3f& tf) {
+void relativeTransform2(const Transform3s& tf1, const Transform3s& tf2,
+                        Transform3s& tf) {
   Matrix3s R(tf2.getRotation() * tf1.getRotation().transpose());
-  tf = Transform3f(R, tf2.getTranslation() - R * tf1.getTranslation());
+  tf = Transform3s(R, tf2.getTranslation() - R * tf1.getTranslation());
 }
 
 }  // namespace coal
diff --git a/src/narrowphase/details.h b/src/narrowphase/details.h
index b6a8b4ae07d9f27bea133fc0a989dd752b1ad534..628953b029d6094de371ac90a439445dfbcfc574 100644
--- a/src/narrowphase/details.h
+++ b/src/narrowphase/details.h
@@ -73,9 +73,9 @@ static inline void lineSegmentPointClosestToPoint(const Vec3s& p,
 /// @param normal pointing from shape 1 to shape 2 (sphere to capsule).
 /// @return the distance between the two shapes (negative if penetration).
 inline CoalScalar sphereCapsuleDistance(const Sphere& s1,
-                                        const Transform3f& tf1,
+                                        const Transform3s& tf1,
                                         const Capsule& s2,
-                                        const Transform3f& tf2, Vec3s& p1,
+                                        const Transform3s& tf2, Vec3s& p1,
                                         Vec3s& p2, Vec3s& normal) {
   Vec3s pos1(tf2.transform(Vec3s(0., 0., s2.halfLength)));
   Vec3s pos2(tf2.transform(Vec3s(0., 0., -s2.halfLength)));
@@ -106,9 +106,9 @@ inline CoalScalar sphereCapsuleDistance(const Sphere& s1,
 /// @param normal pointing from shape 1 to shape 2 (sphere to cylinder).
 /// @return the distance between the two shapes (negative if penetration).
 inline CoalScalar sphereCylinderDistance(const Sphere& s1,
-                                         const Transform3f& tf1,
+                                         const Transform3s& tf1,
                                          const Cylinder& s2,
-                                         const Transform3f& tf2, Vec3s& p1,
+                                         const Transform3s& tf2, Vec3s& p1,
                                          Vec3s& p2, Vec3s& normal) {
   static const CoalScalar eps(sqrt(std::numeric_limits<CoalScalar>::epsilon()));
   CoalScalar r1(s1.radius);
@@ -214,8 +214,8 @@ inline CoalScalar sphereCylinderDistance(const Sphere& s1,
 /// @param p2 witness point on the second Sphere.
 /// @param normal pointing from shape 1 to shape 2 (sphere1 to sphere2).
 /// @return the distance between the two spheres (negative if penetration).
-inline CoalScalar sphereSphereDistance(const Sphere& s1, const Transform3f& tf1,
-                                       const Sphere& s2, const Transform3f& tf2,
+inline CoalScalar sphereSphereDistance(const Sphere& s1, const Transform3s& tf1,
+                                       const Sphere& s2, const Transform3s& tf2,
                                        Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   const coal::Vec3s& center1 = tf1.getTranslation();
   const coal::Vec3s& center2 = tf2.getTranslation();
@@ -286,9 +286,9 @@ inline bool projectInTriangle(const Vec3s& p1, const Vec3s& p2, const Vec3s& p3,
 /// @param normal pointing from shape 1 to shape 2 (sphere1 to sphere2).
 /// @return the distance between the two shapes (negative if penetration).
 inline CoalScalar sphereTriangleDistance(const Sphere& s,
-                                         const Transform3f& tf1,
+                                         const Transform3s& tf1,
                                          const TriangleP& tri,
-                                         const Transform3f& tf2, Vec3s& p1,
+                                         const Transform3s& tf2, Vec3s& p1,
                                          Vec3s& p2, Vec3s& normal) {
   const Vec3s& P1 = tf2.transform(tri.a);
   const Vec3s& P2 = tf2.transform(tri.b);
@@ -347,8 +347,8 @@ inline CoalScalar sphereTriangleDistance(const Sphere& s,
 /// @param p2 closest (or most penetrating) point on the shape,
 /// @param normal the halfspace normal.
 /// @return the distance between the two shapes (negative if penetration).
-inline CoalScalar halfspaceDistance(const Halfspace& h, const Transform3f& tf1,
-                                    const ShapeBase& s, const Transform3f& tf2,
+inline CoalScalar halfspaceDistance(const Halfspace& h, const Transform3s& tf1,
+                                    const ShapeBase& s, const Transform3s& tf2,
                                     Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   // TODO(louis): handle multiple contact points when the halfspace normal is
   // parallel to the shape's surface (every primitive except sphere and
@@ -381,8 +381,8 @@ inline CoalScalar halfspaceDistance(const Halfspace& h, const Transform3f& tf1,
 /// @param p2 closest (or most penetrating) point on the shape,
 /// @param normal the halfspace normal.
 /// @return the distance between the two shapes (negative if penetration).
-inline CoalScalar planeDistance(const Plane& plane, const Transform3f& tf1,
-                                const ShapeBase& s, const Transform3f& tf2,
+inline CoalScalar planeDistance(const Plane& plane, const Transform3s& tf1,
+                                const ShapeBase& s, const Transform3s& tf2,
                                 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   // TODO(louis): handle multiple contact points when the plane normal is
   // parallel to the shape's surface (every primitive except sphere and
@@ -435,8 +435,8 @@ inline CoalScalar planeDistance(const Plane& plane, const Transform3f& tf1,
 /// @param ps the witness point on the sphere.
 /// @param normal pointing from box to sphere
 /// @return the distance between the two shapes (negative if penetration).
-inline CoalScalar boxSphereDistance(const Box& b, const Transform3f& tfb,
-                                    const Sphere& s, const Transform3f& tfs,
+inline CoalScalar boxSphereDistance(const Box& b, const Transform3s& tfb,
+                                    const Sphere& s, const Transform3s& tfs,
                                     Vec3s& pb, Vec3s& ps, Vec3s& normal) {
   const Vec3s& os = tfs.getTranslation();
   const Vec3s& ob = tfb.getTranslation();
@@ -510,9 +510,9 @@ inline CoalScalar boxSphereDistance(const Box& b, const Transform3f& tfb,
 /// intersection line between the objects. The normal is the direction of this
 /// line.
 inline CoalScalar halfspaceHalfspaceDistance(const Halfspace& s1,
-                                             const Transform3f& tf1,
+                                             const Transform3s& tf1,
                                              const Halfspace& s2,
-                                             const Transform3f& tf2, Vec3s& p1,
+                                             const Transform3s& tf2, Vec3s& p1,
                                              Vec3s& p2, Vec3s& normal) {
   Halfspace new_s1 = transform(s1, tf1);
   Halfspace new_s2 = transform(s2, tf2);
@@ -586,9 +586,9 @@ inline CoalScalar halfspaceHalfspaceDistance(const Halfspace& s1,
 /// intersection line between the objects. The normal is the direction of this
 /// line.
 inline CoalScalar halfspacePlaneDistance(const Halfspace& s1,
-                                         const Transform3f& tf1,
+                                         const Transform3s& tf1,
                                          const Plane& s2,
-                                         const Transform3f& tf2, Vec3s& p1,
+                                         const Transform3s& tf2, Vec3s& p1,
                                          Vec3s& p2, Vec3s& normal) {
   Halfspace new_s1 = transform(s1, tf1);
   Plane new_s2 = transform(s2, tf2);
@@ -647,8 +647,8 @@ inline CoalScalar halfspacePlaneDistance(const Halfspace& s1,
 /// The points p1 and p2 are the same point and represent the origin of the
 /// intersection line between the objects. The normal is the direction of this
 /// line.
-inline CoalScalar planePlaneDistance(const Plane& s1, const Transform3f& tf1,
-                                     const Plane& s2, const Transform3f& tf2,
+inline CoalScalar planePlaneDistance(const Plane& s1, const Transform3s& tf1,
+                                     const Plane& s2, const Transform3s& tf2,
                                      Vec3s& p1, Vec3s& p2, Vec3s& normal) {
   Plane new_s1 = transform(s1, tf1);
   Plane new_s2 = transform(s2, tf2);
@@ -722,8 +722,8 @@ inline CoalScalar computePenetration(const Vec3s& P1, const Vec3s& P2,
 inline CoalScalar computePenetration(const Vec3s& P1, const Vec3s& P2,
                                      const Vec3s& P3, const Vec3s& Q1,
                                      const Vec3s& Q2, const Vec3s& Q3,
-                                     const Transform3f& tf1,
-                                     const Transform3f& tf2, Vec3s& normal) {
+                                     const Transform3s& tf1,
+                                     const Transform3s& tf2, Vec3s& normal) {
   Vec3s globalP1(tf1.transform(P1));
   Vec3s globalP2(tf1.transform(P2));
   Vec3s globalP3(tf1.transform(P3));
diff --git a/src/narrowphase/minkowski_difference.cpp b/src/narrowphase/minkowski_difference.cpp
index baa3f4dc96ff18bde1c737f85e16eafbc4a9d310..97c90bb57054a602c9af05370a22ec62e0ae0b86 100644
--- a/src/narrowphase/minkowski_difference.cpp
+++ b/src/narrowphase/minkowski_difference.cpp
@@ -267,7 +267,7 @@ void getNormalizeSupportDirectionFromShapes(const ShapeBase* shape0,
 // ============================================================================
 template <int _SupportOptions>
 void MinkowskiDiff::set(const ShapeBase* shape0, const ShapeBase* shape1,
-                        const Transform3f& tf0, const Transform3f& tf1) {
+                        const Transform3s& tf0, const Transform3s& tf1) {
   shapes[0] = shape0;
   shapes[1] = shape1;
   getNormalizeSupportDirectionFromShapes(shape0, shape1,
@@ -303,9 +303,9 @@ void MinkowskiDiff::set(const ShapeBase* shape0, const ShapeBase* shape1) {
       shape0, shape1, true, swept_sphere_radius, data);
 }
 // clang-format off
-template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&);
+template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3s&, const Transform3s&);
 
-template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&);
+template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3s&, const Transform3s&);
 // clang-format on
 
 // ============================================================================
diff --git a/src/narrowphase/support_functions.cpp b/src/narrowphase/support_functions.cpp
index 64be0e0cc55131761826fcdefedd1cc106d2f11f..a900999d39c911fcc4735e3da62d785f25ce9143 100644
--- a/src/narrowphase/support_functions.cpp
+++ b/src/narrowphase/support_functions.cpp
@@ -569,7 +569,7 @@ void getShapeSupportSet(const Box* box, SupportSet& support_set,
 
   SupportSet::Polygon& polygon = support_data.polygon;
   polygon.clear();
-  const Transform3f& tf = support_set.tf;
+  const Transform3s& tf = support_set.tf;
   for (const Vec3s& corner : corners) {
     const CoalScalar val = corner.dot(support_dir);
     if (support_value - val < tol) {
@@ -813,7 +813,7 @@ void getShapeSupportSetLinear(const ConvexBase* convex, SupportSet& support_set,
   const std::vector<Vec3s>& points = *(convex->points);
   SupportSet::Polygon& polygon = support_data.polygon;
   polygon.clear();
-  const Transform3f& tf = support_set.tf;
+  const Transform3s& tf = support_set.tf;
   for (const Vec3s& point : points) {
     const CoalScalar dot = support_dir.dot(point);
     if (support_value - dot <= tol) {
@@ -840,7 +840,7 @@ void convexSupportSetRecurse(
     const std::vector<ConvexBase::Neighbors>& neighbors,
     const CoalScalar swept_sphere_radius, const size_t vertex_idx,
     const Vec3s& support_dir, const CoalScalar support_value,
-    const Transform3f& tf, std::vector<int8_t>& visited,
+    const Transform3s& tf, std::vector<int8_t>& visited,
     SupportSet::Polygon& polygon, CoalScalar tol) {
   COAL_UNUSED_VARIABLE(swept_sphere_radius);
 
@@ -895,7 +895,7 @@ void getShapeSupportSetLog(const ConvexBase* convex, SupportSet& support_set,
 
   SupportSet::Polygon& polygon = support_data.polygon;
   polygon.clear();
-  const Transform3f& tf = support_set.tf;
+  const Transform3s& tf = support_set.tf;
 
   const size_t vertex_idx = (size_t)(hint);
   convexSupportSetRecurse<_SupportOptions>(
diff --git a/src/shape/geometric_shapes.cpp b/src/shape/geometric_shapes.cpp
index ab6c04a73e3c8d934ed93f9a3bad5444abc842a3..cea609b3fc727d49738ecc84a4d2893ff901aebc 100644
--- a/src/shape/geometric_shapes.cpp
+++ b/src/shape/geometric_shapes.cpp
@@ -142,7 +142,7 @@ void Plane::unitNormalTest() {
 }
 
 void Box::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -153,7 +153,7 @@ void Box::computeLocalAABB() {
 }
 
 void Sphere::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -164,7 +164,7 @@ void Sphere::computeLocalAABB() {
 }
 
 void Ellipsoid::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -175,7 +175,7 @@ void Ellipsoid::computeLocalAABB() {
 }
 
 void Capsule::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -186,7 +186,7 @@ void Capsule::computeLocalAABB() {
 }
 
 void Cone::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -197,7 +197,7 @@ void Cone::computeLocalAABB() {
 }
 
 void Cylinder::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -208,7 +208,7 @@ void Cylinder::computeLocalAABB() {
 }
 
 void ConvexBase::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -219,7 +219,7 @@ void ConvexBase::computeLocalAABB() {
 }
 
 void Halfspace::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -230,7 +230,7 @@ void Halfspace::computeLocalAABB() {
 }
 
 void Plane::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
@@ -241,7 +241,7 @@ void Plane::computeLocalAABB() {
 }
 
 void TriangleP::computeLocalAABB() {
-  computeBV<AABB>(*this, Transform3f(), aabb_local);
+  computeBV<AABB>(*this, Transform3s(), aabb_local);
   const CoalScalar ssr = this->getSweptSphereRadius();
   if (ssr > 0) {
     aabb_local.min_ -= Vec3s::Constant(ssr);
diff --git a/src/shape/geometric_shapes_utility.cpp b/src/shape/geometric_shapes_utility.cpp
index 11960729269d5f0927c5b5d3a63d1c217f631435..a687a8e30f32a0b02a8f7ad97c0ddf05fb28b095 100644
--- a/src/shape/geometric_shapes_utility.cpp
+++ b/src/shape/geometric_shapes_utility.cpp
@@ -43,7 +43,7 @@ namespace coal {
 
 namespace details {
 
-std::vector<Vec3s> getBoundVertices(const Box& box, const Transform3f& tf) {
+std::vector<Vec3s> getBoundVertices(const Box& box, const Transform3s& tf) {
   std::vector<Vec3s> result(8);
   CoalScalar a = box.halfSide[0];
   CoalScalar b = box.halfSide[1];
@@ -62,7 +62,7 @@ std::vector<Vec3s> getBoundVertices(const Box& box, const Transform3f& tf) {
 
 // we use icosahedron to bound the sphere
 std::vector<Vec3s> getBoundVertices(const Sphere& sphere,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(12);
   const CoalScalar m = (1 + sqrt(5.0)) / 2.0;
   CoalScalar edge_size = sphere.radius * 6 / (sqrt(27.0) + sqrt(15.0));
@@ -87,7 +87,7 @@ std::vector<Vec3s> getBoundVertices(const Sphere& sphere,
 
 // we use scaled icosahedron to bound the ellipsoid
 std::vector<Vec3s> getBoundVertices(const Ellipsoid& ellipsoid,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(12);
   const CoalScalar phi = (1 + sqrt(5.0)) / 2.0;
 
@@ -121,7 +121,7 @@ std::vector<Vec3s> getBoundVertices(const Ellipsoid& ellipsoid,
 }
 
 std::vector<Vec3s> getBoundVertices(const Capsule& capsule,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(36);
   const CoalScalar m = (1 + sqrt(5.0)) / 2.0;
 
@@ -176,7 +176,7 @@ std::vector<Vec3s> getBoundVertices(const Capsule& capsule,
   return result;
 }
 
-std::vector<Vec3s> getBoundVertices(const Cone& cone, const Transform3f& tf) {
+std::vector<Vec3s> getBoundVertices(const Cone& cone, const Transform3s& tf) {
   std::vector<Vec3s> result(7);
 
   CoalScalar hl = cone.halfLength;
@@ -197,7 +197,7 @@ std::vector<Vec3s> getBoundVertices(const Cone& cone, const Transform3f& tf) {
 }
 
 std::vector<Vec3s> getBoundVertices(const Cylinder& cylinder,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(12);
 
   CoalScalar hl = cylinder.halfLength;
@@ -223,7 +223,7 @@ std::vector<Vec3s> getBoundVertices(const Cylinder& cylinder,
 }
 
 std::vector<Vec3s> getBoundVertices(const ConvexBase& convex,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(convex.num_points);
   const std::vector<Vec3s>& points_ = *(convex.points);
   for (std::size_t i = 0; i < convex.num_points; ++i) {
@@ -234,7 +234,7 @@ std::vector<Vec3s> getBoundVertices(const ConvexBase& convex,
 }
 
 std::vector<Vec3s> getBoundVertices(const TriangleP& triangle,
-                                    const Transform3f& tf) {
+                                    const Transform3s& tf) {
   std::vector<Vec3s> result(3);
   result[0] = tf.transform(triangle.a);
   result[1] = tf.transform(triangle.b);
@@ -245,7 +245,7 @@ std::vector<Vec3s> getBoundVertices(const TriangleP& triangle,
 
 }  // namespace details
 
-Halfspace transform(const Halfspace& a, const Transform3f& tf) {
+Halfspace transform(const Halfspace& a, const Transform3s& tf) {
   /// suppose the initial halfspace is n * x <= d
   /// after transform (R, T), x --> x' = R x + T
   /// and the new half space becomes n' * x' <= d'
@@ -260,7 +260,7 @@ Halfspace transform(const Halfspace& a, const Transform3f& tf) {
   return result;
 }
 
-Plane transform(const Plane& a, const Transform3f& tf) {
+Plane transform(const Plane& a, const Transform3s& tf) {
   /// suppose the initial halfspace is n * x <= d
   /// after transform (R, T), x --> x' = R x + T
   /// and the new half space becomes n' * x' <= d'
@@ -276,7 +276,7 @@ Plane transform(const Plane& a, const Transform3f& tf) {
 }
 
 std::array<Halfspace, 2> transformToHalfspaces(const Plane& a,
-                                               const Transform3f& tf) {
+                                               const Transform3s& tf) {
   // A plane can be represented by two halfspaces
 
   Vec3s n = tf.getRotation() * a.n;
@@ -289,7 +289,7 @@ std::array<Halfspace, 2> transformToHalfspaces(const Plane& a,
 }
 
 template <>
-void computeBV<AABB, Box>(const Box& s, const Transform3f& tf, AABB& bv) {
+void computeBV<AABB, Box>(const Box& s, const Transform3s& tf, AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
 
@@ -299,7 +299,7 @@ void computeBV<AABB, Box>(const Box& s, const Transform3f& tf, AABB& bv) {
 }
 
 template <>
-void computeBV<AABB, Sphere>(const Sphere& s, const Transform3f& tf, AABB& bv) {
+void computeBV<AABB, Sphere>(const Sphere& s, const Transform3s& tf, AABB& bv) {
   const Vec3s& T = tf.getTranslation();
 
   Vec3s v_delta(Vec3s::Constant(s.radius));
@@ -308,7 +308,7 @@ void computeBV<AABB, Sphere>(const Sphere& s, const Transform3f& tf, AABB& bv) {
 }
 
 template <>
-void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, const Transform3f& tf,
+void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, const Transform3s& tf,
                                 AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
@@ -319,7 +319,7 @@ void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, const Transform3f& tf,
 }
 
 template <>
-void computeBV<AABB, Capsule>(const Capsule& s, const Transform3f& tf,
+void computeBV<AABB, Capsule>(const Capsule& s, const Transform3s& tf,
                               AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
@@ -330,7 +330,7 @@ void computeBV<AABB, Capsule>(const Capsule& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf, AABB& bv) {
+void computeBV<AABB, Cone>(const Cone& s, const Transform3s& tf, AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
 
@@ -347,7 +347,7 @@ void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf, AABB& bv) {
 }
 
 template <>
-void computeBV<AABB, Cylinder>(const Cylinder& s, const Transform3f& tf,
+void computeBV<AABB, Cylinder>(const Cylinder& s, const Transform3s& tf,
                                AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
@@ -365,7 +365,7 @@ void computeBV<AABB, Cylinder>(const Cylinder& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<AABB, ConvexBase>(const ConvexBase& s, const Transform3f& tf,
+void computeBV<AABB, ConvexBase>(const ConvexBase& s, const Transform3s& tf,
                                  AABB& bv) {
   const Matrix3s& R = tf.getRotation();
   const Vec3s& T = tf.getTranslation();
@@ -381,13 +381,13 @@ void computeBV<AABB, ConvexBase>(const ConvexBase& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<AABB, TriangleP>(const TriangleP& s, const Transform3f& tf,
+void computeBV<AABB, TriangleP>(const TriangleP& s, const Transform3s& tf,
                                 AABB& bv) {
   bv = AABB(tf.transform(s.a), tf.transform(s.b), tf.transform(s.c));
 }
 
 template <>
-void computeBV<AABB, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<AABB, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                 AABB& bv) {
   Halfspace new_s = transform(s, tf);
   const Vec3s& n = new_s.n;
@@ -420,7 +420,7 @@ void computeBV<AABB, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<AABB, Plane>(const Plane& s, const Transform3f& tf, AABB& bv) {
+void computeBV<AABB, Plane>(const Plane& s, const Transform3s& tf, AABB& bv) {
   Plane new_s = transform(s, tf);
   const Vec3s& n = new_s.n;
   const CoalScalar& d = new_s.d;
@@ -455,7 +455,7 @@ void computeBV<AABB, Plane>(const Plane& s, const Transform3f& tf, AABB& bv) {
 }
 
 template <>
-void computeBV<OBB, Box>(const Box& s, const Transform3f& tf, OBB& bv) {
+void computeBV<OBB, Box>(const Box& s, const Transform3s& tf, OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -469,7 +469,7 @@ void computeBV<OBB, Box>(const Box& s, const Transform3f& tf, OBB& bv) {
 }
 
 template <>
-void computeBV<OBB, Sphere>(const Sphere& s, const Transform3f& tf, OBB& bv) {
+void computeBV<OBB, Sphere>(const Sphere& s, const Transform3s& tf, OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -482,7 +482,7 @@ void computeBV<OBB, Sphere>(const Sphere& s, const Transform3f& tf, OBB& bv) {
 }
 
 template <>
-void computeBV<OBB, Capsule>(const Capsule& s, const Transform3f& tf, OBB& bv) {
+void computeBV<OBB, Capsule>(const Capsule& s, const Transform3s& tf, OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -496,7 +496,7 @@ void computeBV<OBB, Capsule>(const Capsule& s, const Transform3f& tf, OBB& bv) {
 }
 
 template <>
-void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf, OBB& bv) {
+void computeBV<OBB, Cone>(const Cone& s, const Transform3s& tf, OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -510,7 +510,7 @@ void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf, OBB& bv) {
 }
 
 template <>
-void computeBV<OBB, Cylinder>(const Cylinder& s, const Transform3f& tf,
+void computeBV<OBB, Cylinder>(const Cylinder& s, const Transform3s& tf,
                               OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -525,7 +525,7 @@ void computeBV<OBB, Cylinder>(const Cylinder& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<OBB, ConvexBase>(const ConvexBase& s, const Transform3f& tf,
+void computeBV<OBB, ConvexBase>(const ConvexBase& s, const Transform3s& tf,
                                 OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -542,7 +542,7 @@ void computeBV<OBB, ConvexBase>(const ConvexBase& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<OBB, Halfspace>(const Halfspace& s, const Transform3f&,
+void computeBV<OBB, Halfspace>(const Halfspace& s, const Transform3s&,
                                OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -555,7 +555,7 @@ void computeBV<OBB, Halfspace>(const Halfspace& s, const Transform3f&,
 }
 
 template <>
-void computeBV<RSS, Halfspace>(const Halfspace& s, const Transform3f&,
+void computeBV<RSS, Halfspace>(const Halfspace& s, const Transform3s&,
                                RSS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -569,7 +569,7 @@ void computeBV<RSS, Halfspace>(const Halfspace& s, const Transform3f&,
 }
 
 template <>
-void computeBV<OBBRSS, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<OBBRSS, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                   OBBRSS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -580,7 +580,7 @@ void computeBV<OBBRSS, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<kIOS, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<kIOS, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                 kIOS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -593,7 +593,7 @@ void computeBV<kIOS, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                     KDOP<16>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -653,7 +653,7 @@ void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                     KDOP<18>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -719,7 +719,7 @@ void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, const Transform3f& tf,
+void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, const Transform3s& tf,
                                     KDOP<24>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -800,7 +800,7 @@ void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf, OBB& bv) {
+void computeBV<OBB, Plane>(const Plane& s, const Transform3s& tf, OBB& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -818,7 +818,7 @@ void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf, OBB& bv) {
 }
 
 template <>
-void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf, RSS& bv) {
+void computeBV<RSS, Plane>(const Plane& s, const Transform3s& tf, RSS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -838,7 +838,7 @@ void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf, RSS& bv) {
 }
 
 template <>
-void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3f& tf,
+void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3s& tf,
                               OBBRSS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -849,7 +849,7 @@ void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<kIOS, Plane>(const Plane& s, const Transform3f& tf, kIOS& bv) {
+void computeBV<kIOS, Plane>(const Plane& s, const Transform3s& tf, kIOS& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
                       std::runtime_error);
@@ -861,7 +861,7 @@ void computeBV<kIOS, Plane>(const Plane& s, const Transform3f& tf, kIOS& bv) {
 }
 
 template <>
-void computeBV<KDOP<16>, Plane>(const Plane& s, const Transform3f& tf,
+void computeBV<KDOP<16>, Plane>(const Plane& s, const Transform3s& tf,
                                 KDOP<16>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -907,7 +907,7 @@ void computeBV<KDOP<16>, Plane>(const Plane& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<KDOP<18>, Plane>(const Plane& s, const Transform3f& tf,
+void computeBV<KDOP<18>, Plane>(const Plane& s, const Transform3s& tf,
                                 KDOP<18>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -955,7 +955,7 @@ void computeBV<KDOP<18>, Plane>(const Plane& s, const Transform3f& tf,
 }
 
 template <>
-void computeBV<KDOP<24>, Plane>(const Plane& s, const Transform3f& tf,
+void computeBV<KDOP<24>, Plane>(const Plane& s, const Transform3s& tf,
                                 KDOP<24>& bv) {
   if (s.getSweptSphereRadius() > 0) {
     COAL_THROW_PRETTY("Swept-sphere radius not yet supported.",
@@ -1008,92 +1008,92 @@ void computeBV<KDOP<24>, Plane>(const Plane& s, const Transform3f& tf,
   }
 }
 
-void constructBox(const AABB& bv, Box& box, Transform3f& tf) {
+void constructBox(const AABB& bv, Box& box, Transform3s& tf) {
   box = Box(bv.max_ - bv.min_);
-  tf = Transform3f(bv.center());
+  tf = Transform3s(bv.center());
 }
 
-void constructBox(const OBB& bv, Box& box, Transform3f& tf) {
+void constructBox(const OBB& bv, Box& box, Transform3s& tf) {
   box = Box(bv.extent * 2);
-  tf = Transform3f(bv.axes, bv.To);
+  tf = Transform3s(bv.axes, bv.To);
 }
 
-void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf) {
+void constructBox(const OBBRSS& bv, Box& box, Transform3s& tf) {
   box = Box(bv.obb.extent * 2);
-  tf = Transform3f(bv.obb.axes, bv.obb.To);
+  tf = Transform3s(bv.obb.axes, bv.obb.To);
 }
 
-void constructBox(const kIOS& bv, Box& box, Transform3f& tf) {
+void constructBox(const kIOS& bv, Box& box, Transform3s& tf) {
   box = Box(bv.obb.extent * 2);
-  tf = Transform3f(bv.obb.axes, bv.obb.To);
+  tf = Transform3s(bv.obb.axes, bv.obb.To);
 }
 
-void constructBox(const RSS& bv, Box& box, Transform3f& tf) {
+void constructBox(const RSS& bv, Box& box, Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = Transform3f(bv.axes, bv.Tr);
+  tf = Transform3s(bv.axes, bv.Tr);
 }
 
-void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf) {
+void constructBox(const KDOP<16>& bv, Box& box, Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = Transform3f(bv.center());
+  tf = Transform3s(bv.center());
 }
 
-void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf) {
+void constructBox(const KDOP<18>& bv, Box& box, Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = Transform3f(bv.center());
+  tf = Transform3s(bv.center());
 }
 
-void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf) {
+void constructBox(const KDOP<24>& bv, Box& box, Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = Transform3f(bv.center());
+  tf = Transform3s(bv.center());
 }
 
-void constructBox(const AABB& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const AABB& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.max_ - bv.min_);
-  tf = tf_bv * Transform3f(bv.center());
+  tf = tf_bv * Transform3s(bv.center());
 }
 
-void constructBox(const OBB& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const OBB& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.extent * 2);
-  tf = tf_bv * Transform3f(bv.axes, bv.To);
+  tf = tf_bv * Transform3s(bv.axes, bv.To);
 }
 
-void constructBox(const OBBRSS& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const OBBRSS& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.obb.extent * 2);
-  tf = tf_bv * Transform3f(bv.obb.axes, bv.obb.To);
+  tf = tf_bv * Transform3s(bv.obb.axes, bv.obb.To);
 }
 
-void constructBox(const kIOS& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const kIOS& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.obb.extent * 2);
-  tf = tf_bv * Transform3f(bv.obb.axes, bv.obb.To);
+  tf = tf_bv * Transform3s(bv.obb.axes, bv.obb.To);
 }
 
-void constructBox(const RSS& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const RSS& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = tf_bv * Transform3f(bv.axes, bv.Tr);
+  tf = tf_bv * Transform3s(bv.axes, bv.Tr);
 }
 
-void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const KDOP<16>& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = tf_bv * Transform3f(bv.center());
+  tf = tf_bv * Transform3s(bv.center());
 }
 
-void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const KDOP<18>& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = tf_bv * Transform3f(bv.center());
+  tf = tf_bv * Transform3s(bv.center());
 }
 
-void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv, Box& box,
-                  Transform3f& tf) {
+void constructBox(const KDOP<24>& bv, const Transform3s& tf_bv, Box& box,
+                  Transform3s& tf) {
   box = Box(bv.width(), bv.height(), bv.depth());
-  tf = tf_bv * Transform3f(bv.center());
+  tf = tf_bv * Transform3s(bv.center());
 }
 
 }  // namespace coal
diff --git a/test/accelerated_gjk.cpp b/test/accelerated_gjk.cpp
index 624c422a4c09fac7ef29a72f656821475ea8843c..367b49aa44aff82bf56a59fa114d27d088e2284c 100644
--- a/test/accelerated_gjk.cpp
+++ b/test/accelerated_gjk.cpp
@@ -54,7 +54,7 @@ using coal::GJKSolver;
 using coal::GJKVariant;
 using coal::ShapeBase;
 using coal::support_func_guess_t;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Triangle;
 using coal::Vec3s;
 using coal::details::GJK;
@@ -120,9 +120,9 @@ void test_accelerated_gjk(const ShapeBase& shape0, const ShapeBase& shape1) {
   // Generate random transforms
   size_t n = 1000;
   CoalScalar extents[] = {-3., -3., 0, 3., 3., 3.};
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
-  Transform3f identity = Transform3f::Identity();
+  Transform3s identity = Transform3s::Identity();
 
   // Same init for both solvers
   Vec3s init_guess = Vec3s(1, 0, 0);
diff --git a/test/benchmark.cpp b/test/benchmark.cpp
index 2f7b37422ad21f4f317121e568253c8953690449..fd1e973c4b69db6969a8715c647b416e24e784f1 100644
--- a/test/benchmark.cpp
+++ b/test/benchmark.cpp
@@ -38,15 +38,15 @@ void makeModel(const std::vector<Vec3s>& vertices,
                SplitMethodType split_method, BVHModel<BV>& model);
 
 template <typename BV, typename TraversalNode>
-double distance(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
+double distance(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
                 const BVHModel<BV>& m2, bool verbose);
 
 template <typename BV, typename TraversalNode>
-double collide(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
+double collide(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
                const BVHModel<BV>& m2, bool verbose);
 
 template <typename BV>
-double run(const std::vector<Transform3f>& tf,
+double run(const std::vector<Transform3s>& tf,
            const BVHModel<BV> (&models)[2][3], int split_method,
            const char* sm_name);
 
@@ -90,9 +90,9 @@ void makeModel(const std::vector<Vec3s>& vertices,
 }
 
 template <typename BV, typename TraversalNode>
-double distance(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
+double distance(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
                 const BVHModel<BV>& m2, bool verbose) {
-  Transform3f pose2;
+  Transform3s pose2;
 
   DistanceResult local_result;
   DistanceRequest request(true);
@@ -114,9 +114,9 @@ double distance(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
 }
 
 template <typename BV, typename TraversalNode>
-double collide(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
+double collide(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
                const BVHModel<BV>& m2, bool verbose) {
-  Transform3f pose2;
+  Transform3s pose2;
 
   CollisionResult local_result;
   CollisionRequest request;
@@ -141,7 +141,7 @@ double collide(const std::vector<Transform3f>& tf, const BVHModel<BV>& m1,
 }
 
 template <typename BV>
-double run(const std::vector<Transform3f>& tf,
+double run(const std::vector<Transform3s>& tf,
            const BVHModel<BV> (&models)[2][3], int split_method,
            const char* prefix) {
   double col = collide<BV, typename traits<BV>::CollisionTraversalNode>(
@@ -154,7 +154,7 @@ double run(const std::vector<Transform3f>& tf,
 }
 
 template <>
-double run<OBB>(const std::vector<Transform3f>& tf,
+double run<OBB>(const std::vector<Transform3s>& tf,
                 const BVHModel<OBB> (&models)[2][3], int split_method,
                 const char* prefix) {
   double col = collide<OBB, traits<OBB>::CollisionTraversalNode>(
@@ -207,7 +207,7 @@ int main(int, char*[]) {
             ms_obbrss[1][SPLIT_METHOD_BV_CENTER]);
   makeModel(p2, t2, SPLIT_METHOD_MEDIAN, ms_obbrss[1][SPLIT_METHOD_MEDIAN]);
 
-  std::vector<Transform3f> transforms;  // t0
+  std::vector<Transform3s> transforms;  // t0
   CoalScalar extents[] = {-3000, -3000, -3000, 3000, 3000, 3000};
   std::size_t n = 10000;
 
diff --git a/test/box_box_collision.cpp b/test/box_box_collision.cpp
index 8a99e3b11d4789f6b41feaeba3c4f1e834975761..63c1f4fcf5a824cdf85bf31b383fca6563dd57a4 100644
--- a/test/box_box_collision.cpp
+++ b/test/box_box_collision.cpp
@@ -14,7 +14,7 @@ using coal::collide;
 using coal::CollisionRequest;
 using coal::CollisionResult;
 using coal::ComputeCollision;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Vec3s;
 
 BOOST_AUTO_TEST_CASE(box_box_collision) {
@@ -23,8 +23,8 @@ BOOST_AUTO_TEST_CASE(box_box_collision) {
   Box shape2(1, 1, 1);
 
   // Define transforms
-  Transform3f T1 = Transform3f::Identity();
-  Transform3f T2 = Transform3f::Identity();
+  Transform3s T1 = Transform3s::Identity();
+  Transform3s T2 = Transform3s::Identity();
 
   // Compute collision
   CollisionRequest req;
diff --git a/test/box_box_distance.cpp b/test/box_box_distance.cpp
index dc5189a1e0473dd5880d9c1f53a0f16b9851ef8c..82ff5bfeeb66352a570d5566f5c308feadcdae45 100644
--- a/test/box_box_distance.cpp
+++ b/test/box_box_distance.cpp
@@ -56,15 +56,15 @@ using coal::CollisionGeometryPtr_t;
 using coal::CollisionObject;
 using coal::DistanceRequest;
 using coal::DistanceResult;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Vec3s;
 
 BOOST_AUTO_TEST_CASE(distance_box_box_1) {
   CollisionGeometryPtr_t s1(new coal::Box(6, 10, 2));
   CollisionGeometryPtr_t s2(new coal::Box(2, 2, 2));
 
-  Transform3f tf1;
-  Transform3f tf2(Vec3s(25, 20, 5));
+  Transform3s tf1;
+  Transform3s tf2(Vec3s(25, 20, 5));
 
   CollisionObject o1(s1, tf1);
   CollisionObject o2(s2, tf2);
@@ -104,8 +104,8 @@ BOOST_AUTO_TEST_CASE(distance_box_box_2) {
   CollisionGeometryPtr_t s1(new coal::Box(6, 10, 2));
   CollisionGeometryPtr_t s2(new coal::Box(2, 2, 2));
   static double pi = M_PI;
-  Transform3f tf1;
-  Transform3f tf2(coal::makeQuat(cos(pi / 8), sin(pi / 8) / sqrt(3),
+  Transform3s tf1;
+  Transform3s tf2(coal::makeQuat(cos(pi / 8), sin(pi / 8) / sqrt(3),
                                  sin(pi / 8) / sqrt(3), sin(pi / 8) / sqrt(3)),
                   Vec3s(0, 0, 10));
 
@@ -144,9 +144,9 @@ BOOST_AUTO_TEST_CASE(distance_box_box_3) {
   CollisionGeometryPtr_t s1(new coal::Box(1, 1, 1));
   CollisionGeometryPtr_t s2(new coal::Box(1, 1, 1));
   static double pi = M_PI;
-  Transform3f tf1(coal::makeQuat(cos(pi / 8), 0, 0, sin(pi / 8)),
+  Transform3s tf1(coal::makeQuat(cos(pi / 8), 0, 0, sin(pi / 8)),
                   Vec3s(-2, 1, .5));
-  Transform3f tf2(coal::makeQuat(cos(pi / 8), 0, sin(pi / 8), 0),
+  Transform3s tf2(coal::makeQuat(cos(pi / 8), 0, sin(pi / 8), 0),
                   Vec3s(2, .5, .5));
 
   CollisionObject o1(s1, tf1);
@@ -182,7 +182,7 @@ BOOST_AUTO_TEST_CASE(distance_box_box_3) {
   BOOST_CHECK_CLOSE(p2[2], p2Ref[2], 1e-4);
 
   // Apply the same global transform to both objects and recompute
-  Transform3f tf3(coal::makeQuat(0.435952844074, -0.718287018243,
+  Transform3s tf3(coal::makeQuat(0.435952844074, -0.718287018243,
                                  0.310622451066, 0.444435113443),
                   Vec3s(4, 5, 6));
   tf1 = tf3 * tf1;
@@ -223,8 +223,8 @@ BOOST_AUTO_TEST_CASE(distance_box_box_4) {
   DistanceResult distanceResult;
   double distance;
 
-  Transform3f tf1(Vec3s(2, 0, 0));
-  Transform3f tf2;
+  Transform3s tf1(Vec3s(2, 0, 0));
+  Transform3s tf2;
   coal::distance(&s1, tf1, &s2, tf2, distanceRequest, distanceResult);
 
   distance = 1.;
diff --git a/test/broadphase.cpp b/test/broadphase.cpp
index 8750e55d0f23075f0c5d04a2f86d0d7827ac665d..a28b85636ce85e4aab55aef788faa8549d773edd 100644
--- a/test/broadphase.cpp
+++ b/test/broadphase.cpp
@@ -159,7 +159,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env,
     Box* box = new Box(single_size, single_size, single_size);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(box),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -174,7 +174,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env,
     Sphere* sphere = new Sphere(single_size / 2);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(sphere),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -189,7 +189,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env,
     Cylinder* cylinder = new Cylinder(single_size / 2, single_size);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(cylinder),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -204,7 +204,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env,
     Cone* cone = new Cone(single_size / 2, single_size);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(cone),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -228,10 +228,10 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env,
 
     Box box(single_size, single_size, single_size);
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, box, Transform3f());
+    generateBVHModel(*model, box, Transform3s());
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(model),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -245,10 +245,10 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env,
 
     Sphere sphere(single_size / 2);
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, sphere, Transform3f(), 16, 16);
+    generateBVHModel(*model, sphere, Transform3s(), 16, 16);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(model),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -262,10 +262,10 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env,
 
     Cylinder cylinder(single_size / 2, single_size);
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, cylinder, Transform3f(), 16, 16);
+    generateBVHModel(*model, cylinder, Transform3s(), 16, 16);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(model),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
@@ -279,10 +279,10 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env,
 
     Cone cone(single_size / 2, single_size);
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, cone, Transform3f(), 16, 16);
+    generateBVHModel(*model, cone, Transform3s(), 16, 16);
     env.push_back(new CollisionObject(
         shared_ptr<CollisionGeometry>(model),
-        Transform3f(Vec3s(
+        Transform3s(Vec3s(
             x * step_size + delta_size + 0.5 * single_size - env_scale,
             y * step_size + delta_size + 0.5 * single_size - env_scale,
             z * step_size + delta_size + 0.5 * single_size - env_scale))));
diff --git a/test/bvh_models.cpp b/test/bvh_models.cpp
index b4abb8618e653e4f62a29bd0d612b582c4e1ea2c..74a946621e7b9ee6cbf2a26d2cc2f11e55e02901 100644
--- a/test/bvh_models.cpp
+++ b/test/bvh_models.cpp
@@ -190,7 +190,7 @@ void testBVHModelTriangles() {
   BOOST_CHECK_EQUAL(model->num_tris, 12);
   BOOST_CHECK_EQUAL(model->build_state, BVH_BUILD_STATE_PROCESSED);
 
-  Transform3f pose;
+  Transform3s pose;
   shared_ptr<BVHModel<BV> > cropped(BVHExtract(*model, pose, aabb));
   BOOST_REQUIRE(cropped);
   BOOST_CHECK(cropped->build_state == BVH_BUILD_STATE_PROCESSED);
@@ -335,7 +335,7 @@ void testLoadGerardBauzil() {
   scale.setConstant(1);
   loadPolyhedronFromResource(env, scale, P1);
   CollisionGeometryPtr_t cylinder(new Cylinder(.27, .27));
-  Transform3f pos(Vec3s(-1.33, 1.36, .14));
+  Transform3s pos(Vec3s(-1.33, 1.36, .14));
   CollisionObject obj(cylinder, pos);
   CollisionObject stairs(P1);
 
@@ -376,7 +376,7 @@ BOOST_AUTO_TEST_CASE(test_convex) {
   Box* box_ptr = new coal::Box(1, 1, 1);
   CollisionGeometryPtr_t b1(box_ptr);
   BVHModel<OBBRSS> box_bvh_model = BVHModel<OBBRSS>();
-  generateBVHModel(box_bvh_model, *box_ptr, Transform3f());
+  generateBVHModel(box_bvh_model, *box_ptr, Transform3s());
   box_bvh_model.buildConvexRepresentation(false);
 
   box_bvh_model.convex->computeLocalAABB();
diff --git a/test/capsule_box_1.cpp b/test/capsule_box_1.cpp
index 386aecf4653246c9978210d3c16cfe93c92a79e0..30b882b027b598b548f4fd17c2db627fe8fc8d6f 100644
--- a/test/capsule_box_1.cpp
+++ b/test/capsule_box_1.cpp
@@ -59,8 +59,8 @@ BOOST_AUTO_TEST_CASE(distance_capsule_box) {
   coal::DistanceRequest distanceRequest(true, 0, 0);
   coal::DistanceResult distanceResult;
 
-  coal::Transform3f tf1(coal::Vec3s(3., 0, 0));
-  coal::Transform3f tf2;
+  coal::Transform3s tf1(coal::Vec3s(3., 0, 0));
+  coal::Transform3s tf2;
   coal::CollisionObject capsule(capsuleGeometry, tf1);
   coal::CollisionObject box(boxGeometry, tf2);
 
@@ -77,7 +77,7 @@ BOOST_AUTO_TEST_CASE(distance_capsule_box) {
   CHECK_CLOSE_TO_0(o2[1], 1e-1);
 
   // Move capsule above box
-  tf1 = coal::Transform3f(coal::Vec3s(0., 0., 8.));
+  tf1 = coal::Transform3s(coal::Vec3s(0., 0., 8.));
   capsule.setTransform(tf1);
 
   // test distance
diff --git a/test/capsule_box_2.cpp b/test/capsule_box_2.cpp
index 8e3bb3ba7e51cfa954817096a5410e6316e27a89..bdf84d5922dd68718f2d3d578cb9a4eaa7797aa1 100644
--- a/test/capsule_box_2.cpp
+++ b/test/capsule_box_2.cpp
@@ -60,9 +60,9 @@ BOOST_AUTO_TEST_CASE(distance_capsule_box) {
   coal::DistanceResult distanceResult;
 
   // Rotate capsule around y axis by pi/2 and move it behind box
-  coal::Transform3f tf1(coal::makeQuat(sqrt(2) / 2, 0, sqrt(2) / 2, 0),
+  coal::Transform3s tf1(coal::makeQuat(sqrt(2) / 2, 0, sqrt(2) / 2, 0),
                         coal::Vec3s(-10., 0.8, 1.5));
-  coal::Transform3f tf2;
+  coal::Transform3s tf2;
   coal::CollisionObject capsule(capsuleGeometry, tf1);
   coal::CollisionObject box(boxGeometry, tf2);
 
diff --git a/test/capsule_capsule.cpp b/test/capsule_capsule.cpp
index 4534af24360892e5c94b63401236ba09dad5347f..b3f3e53047c92ec7be3da87e8d6751cfafa43d81 100644
--- a/test/capsule_capsule.cpp
+++ b/test/capsule_capsule.cpp
@@ -68,8 +68,8 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_trivial) {
   int num_tests = 1e6;
 #endif
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   for (int i = 0; i < num_tests; ++i) {
     Eigen::Vector3d p1 = Eigen::Vector3d::Random() * (2. * radius);
@@ -121,8 +121,8 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_aligned) {
   int num_tests = 1e6;
 #endif
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   Eigen::Vector3d p1 = Eigen::Vector3d::Zero();
   Eigen::Vector3d p2_no_collision =
@@ -180,9 +180,9 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_aligned) {
 
   p2_no_collision = Eigen::Vector3d(0., 0., 2 * (length / 2. + radius) + 1e-3);
 
-  Transform3f geom1_placement(Eigen::Matrix3d::Identity(),
+  Transform3s geom1_placement(Eigen::Matrix3d::Identity(),
                               Eigen::Vector3d::Zero());
-  Transform3f geom2_placement(Eigen::Matrix3d::Identity(), p2_no_collision);
+  Transform3s geom2_placement(Eigen::Matrix3d::Identity(), p2_no_collision);
 
   for (int i = 0; i < num_tests; ++i) {
     Eigen::Matrix3d rot =
@@ -190,9 +190,9 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_aligned) {
             .toRotationMatrix();
     Eigen::Vector3d trans = Eigen::Vector3d::Random();
 
-    Transform3f displacement(rot, trans);
-    Transform3f tf1 = displacement * geom1_placement;
-    Transform3f tf2 = displacement * geom2_placement;
+    Transform3s displacement(rot, trans);
+    Transform3s tf1 = displacement * geom1_placement;
+    Transform3s tf2 = displacement * geom2_placement;
 
     CollisionObject capsule_o1(c1, tf1);
     CollisionObject capsule_o2(c2, tf2);
@@ -218,9 +218,9 @@ BOOST_AUTO_TEST_CASE(collision_capsule_capsule_aligned) {
             .toRotationMatrix();
     Eigen::Vector3d trans = Eigen::Vector3d::Random();
 
-    Transform3f displacement(rot, trans);
-    Transform3f tf1 = displacement * geom1_placement;
-    Transform3f tf2 = displacement * geom2_placement;
+    Transform3s displacement(rot, trans);
+    Transform3s tf1 = displacement * geom1_placement;
+    Transform3s tf2 = displacement * geom2_placement;
 
     CollisionObject capsule_o1(c1, tf1);
     CollisionObject capsule_o2(c2, tf2);
@@ -240,8 +240,8 @@ BOOST_AUTO_TEST_CASE(distance_capsulecapsule_origin) {
   CollisionGeometryPtr_t s1(new Capsule(5, 10));
   CollisionGeometryPtr_t s2(new Capsule(5, 10));
 
-  Transform3f tf1;
-  Transform3f tf2(Vec3s(20.1, 0, 0));
+  Transform3s tf1;
+  Transform3s tf2(Vec3s(20.1, 0, 0));
 
   CollisionObject o1(s1, tf1);
   CollisionObject o2(s2, tf2);
@@ -266,8 +266,8 @@ BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformXY) {
   CollisionGeometryPtr_t s1(new Capsule(5, 10));
   CollisionGeometryPtr_t s2(new Capsule(5, 10));
 
-  Transform3f tf1;
-  Transform3f tf2(Vec3s(20, 20, 0));
+  Transform3s tf1;
+  Transform3s tf2(Vec3s(20, 20, 0));
 
   CollisionObject o1(s1, tf1);
   CollisionObject o2(s2, tf2);
@@ -293,8 +293,8 @@ BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformZ) {
   CollisionGeometryPtr_t s1(new Capsule(5, 10));
   CollisionGeometryPtr_t s2(new Capsule(5, 10));
 
-  Transform3f tf1;
-  Transform3f tf2(Vec3s(0, 0, 20.1));
+  Transform3s tf1;
+  Transform3s tf2(Vec3s(0, 0, 20.1));
 
   CollisionObject o1(s1, tf1);
   CollisionObject o2(s2, tf2);
@@ -319,8 +319,8 @@ BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformZ2) {
   CollisionGeometryPtr_t s1(new Capsule(5, 10));
   CollisionGeometryPtr_t s2(new Capsule(5, 10));
 
-  Transform3f tf1;
-  Transform3f tf2(makeQuat(sqrt(2) / 2, 0, sqrt(2) / 2, 0), Vec3s(0, 0, 25.1));
+  Transform3s tf1;
+  Transform3s tf2(makeQuat(sqrt(2) / 2, 0, sqrt(2) / 2, 0), Vec3s(0, 0, 25.1));
 
   CollisionObject o1(s1, tf1);
   CollisionObject o2(s2, tf2);
diff --git a/test/collision.cpp b/test/collision.cpp
index d0295994833fd635952f98c3286ca266561bbadb..04bddb945b219ca3d79c779479f68c7db8f62498 100644
--- a/test/collision.cpp
+++ b/test/collision.cpp
@@ -74,7 +74,7 @@ int num_max_contacts = (std::numeric_limits<int>::max)();
 
 BOOST_AUTO_TEST_CASE(OBB_Box_test) {
   CoalScalar r_extents[] = {-1000, -1000, -1000, 1000, 1000, 1000};
-  std::vector<Transform3f> rotate_transform;
+  std::vector<Transform3s> rotate_transform;
   generateRandomTransforms(r_extents, rotate_transform, 1);
 
   AABB aabb1;
@@ -84,13 +84,13 @@ BOOST_AUTO_TEST_CASE(OBB_Box_test) {
   OBB obb1;
   convertBV(aabb1, rotate_transform[0], obb1);
   Box box1;
-  Transform3f box1_tf;
+  Transform3s box1_tf;
   constructBox(aabb1, rotate_transform[0], box1, box1_tf);
 
   CoalScalar extents[] = {-1000, -1000, -1000, 1000, 1000, 1000};
   std::size_t n = 1000;
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
 
   for (std::size_t i = 0; i < transforms.size(); ++i) {
@@ -102,7 +102,7 @@ BOOST_AUTO_TEST_CASE(OBB_Box_test) {
     convertBV(aabb, transforms[i], obb2);
 
     Box box2;
-    Transform3f box2_tf;
+    Transform3s box2_tf;
     constructBox(aabb, transforms[i], box2, box2_tf);
 
     GJKSolver solver;
@@ -124,7 +124,7 @@ BOOST_AUTO_TEST_CASE(OBB_Box_test) {
 
 BOOST_AUTO_TEST_CASE(OBB_shape_test) {
   CoalScalar r_extents[] = {-1000, -1000, -1000, 1000, 1000, 1000};
-  std::vector<Transform3f> rotate_transform;
+  std::vector<Transform3s> rotate_transform;
   generateRandomTransforms(r_extents, rotate_transform, 1);
 
   AABB aabb1;
@@ -134,13 +134,13 @@ BOOST_AUTO_TEST_CASE(OBB_shape_test) {
   OBB obb1;
   convertBV(aabb1, rotate_transform[0], obb1);
   Box box1;
-  Transform3f box1_tf;
+  Transform3s box1_tf;
   constructBox(aabb1, rotate_transform[0], box1, box1_tf);
 
   CoalScalar extents[] = {-1000, -1000, -1000, 1000, 1000, 1000};
   std::size_t n = 1000;
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
 
   for (std::size_t i = 0; i < transforms.size(); ++i) {
@@ -209,7 +209,7 @@ BOOST_AUTO_TEST_CASE(OBB_AABB_test) {
   CoalScalar extents[] = {-1000, -1000, -1000, 1000, 1000, 1000};
   std::size_t n = 1000;
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
 
   AABB aabb1;
@@ -217,7 +217,7 @@ BOOST_AUTO_TEST_CASE(OBB_AABB_test) {
   aabb1.max_ = Vec3s(600, 600, 600);
 
   OBB obb1;
-  convertBV(aabb1, Transform3f(), obb1);
+  convertBV(aabb1, Transform3s(), obb1);
 
   for (std::size_t i = 0; i < transforms.size(); ++i) {
     AABB aabb;
@@ -227,7 +227,7 @@ BOOST_AUTO_TEST_CASE(OBB_AABB_test) {
     AABB aabb2 = translate(aabb, transforms[i].getTranslation());
 
     OBB obb2;
-    convertBV(aabb, Transform3f(transforms[i].getTranslation()), obb2);
+    convertBV(aabb, Transform3s(transforms[i].getTranslation()), obb2);
 
     bool overlap_aabb = aabb1.overlap(aabb2);
     bool overlap_obb = obb1.overlap(obb2);
@@ -312,7 +312,7 @@ HPP_FCL_COMPILER_DIAGNOSTIC_PUSH
 HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
 
 struct mesh_mesh_run_test {
-  mesh_mesh_run_test(const std::vector<Transform3f>& _transforms,
+  mesh_mesh_run_test(const std::vector<Transform3s>& _transforms,
                      const CollisionRequest _request)
       : transforms(_transforms),
         request(_request),
@@ -321,7 +321,7 @@ struct mesh_mesh_run_test {
         isInit(false),
         indent(0) {}
 
-  const std::vector<Transform3f>& transforms;
+  const std::vector<Transform3s>& transforms;
   const CollisionRequest request;
   bool enable_statistics, benchmark;
   std::vector<Contacts_t> contacts;
@@ -347,7 +347,7 @@ struct mesh_mesh_run_test {
   }
 
   template <typename BV>
-  void query(const std::vector<Transform3f>& transforms,
+  void query(const std::vector<Transform3s>& transforms,
              SplitMethodType splitMethod, const CollisionRequest request,
              std::vector<Contacts_t>& contacts) {
     BENCHMARK_HEADER("BV");
@@ -375,7 +375,7 @@ struct mesh_mesh_run_test {
                                model2);
 
     Timer timer(false);
-    const Transform3f tf2;
+    const Transform3s tf2;
     const std::size_t N = transforms.size();
 
     contacts.resize(3 * N);
@@ -385,7 +385,7 @@ struct mesh_mesh_run_test {
       ++indent;
 
       for (std::size_t i = 0; i < transforms.size(); ++i) {
-        const Transform3f& tf1 = transforms[i];
+        const Transform3s& tf1 = transforms[i];
         timer.start();
 
         CollisionResult local_result;
@@ -429,7 +429,7 @@ struct mesh_mesh_run_test {
       ++indent;
 
       for (std::size_t i = 0; i < transforms.size(); ++i) {
-        const Transform3f tf1 = transforms[i];
+        const Transform3s tf1 = transforms[i];
 
         timer.start();
         CollisionResult local_result;
@@ -438,9 +438,9 @@ struct mesh_mesh_run_test {
         node.enable_statistics = enable_statistics;
 
         BVH_t* model1_tmp = new BVH_t(*model1);
-        Transform3f tf1_tmp = tf1;
+        Transform3s tf1_tmp = tf1;
         BVH_t* model2_tmp = new BVH_t(*model2);
-        Transform3f tf2_tmp = tf2;
+        Transform3s tf2_tmp = tf2;
 
         bool success = initialize(node, *model1_tmp, tf1_tmp, *model2_tmp,
                                   tf2_tmp, local_result, true, true);
@@ -482,7 +482,7 @@ struct mesh_mesh_run_test {
 
       for (std::size_t i = 0; i < transforms.size(); ++i) {
         timer.start();
-        const Transform3f tf1 = transforms[i];
+        const Transform3s tf1 = transforms[i];
 
         CollisionResult local_result;
         MeshCollisionTraversalNode<BV, 0> node(request);
@@ -623,7 +623,7 @@ struct mesh_mesh_run_test {
 //      calls function collide with identity for both object poses,
 //
 BOOST_AUTO_TEST_CASE(mesh_mesh) {
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
 #ifndef NDEBUG  // if debug mode
   std::size_t n = 1;
@@ -654,7 +654,7 @@ BOOST_AUTO_TEST_CASE(mesh_mesh) {
 }
 
 BOOST_AUTO_TEST_CASE(mesh_mesh_benchmark) {
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
 #ifndef NDEBUG
   std::size_t n = 0;
diff --git a/test/collision_node_asserts.cpp b/test/collision_node_asserts.cpp
index 3214a96c18f6b3e40a80acd35499fd45554c6e47..698d1d5b46e89963560a1d54b230e5837482726a 100644
--- a/test/collision_node_asserts.cpp
+++ b/test/collision_node_asserts.cpp
@@ -36,8 +36,8 @@ BOOST_AUTO_TEST_CASE(TestTriangles) {
 
   ComputeCollision compute(&tri1, &tri2);
 
-  Transform3f tri1Tf{};
-  Transform3f tri2Tf{};
+  Transform3s tri1Tf{};
+  Transform3s tri2Tf{};
 
   /// check some angles for two triangles
   for (int i = 0; i < 360; i += 30) {
diff --git a/test/contact_patch.cpp b/test/contact_patch.cpp
index 6db7f1069e282c066a36e47b2601ab53527f2a9c..a78b84f446cf8f821aecdc108e12a19dc95ee038 100644
--- a/test/contact_patch.cpp
+++ b/test/contact_patch.cpp
@@ -48,8 +48,8 @@ BOOST_AUTO_TEST_CASE(box_box_no_collision) {
   const Box box1(2 * halfside, 2 * halfside, 2 * halfside);
   const Box box2(2 * halfside, 2 * halfside, 2 * halfside);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to separate the shapes
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, 2 * halfside + offset));
@@ -75,8 +75,8 @@ BOOST_AUTO_TEST_CASE(box_sphere) {
   const Box box(2 * halfside, 2 * halfside, 2 * halfside);
   const Sphere sphere(halfside);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, 2 * halfside - offset));
@@ -113,8 +113,8 @@ BOOST_AUTO_TEST_CASE(box_box) {
   const Box box1(2 * halfside, 2 * halfside, 2 * halfside);
   const Box box2(2 * halfside, 2 * halfside, 2 * halfside);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, 2 * halfside - offset));
@@ -171,8 +171,8 @@ BOOST_AUTO_TEST_CASE(halfspace_box) {
   const CoalScalar halfside = 0.5;
   const Box box(2 * halfside, 2 * halfside, 2 * halfside);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, halfside - offset));
@@ -231,8 +231,8 @@ BOOST_AUTO_TEST_CASE(halfspace_capsule) {
   const CoalScalar height = 1.;
   const Capsule capsule(radius, height);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, height / 2 - offset));
@@ -343,8 +343,8 @@ BOOST_AUTO_TEST_CASE(halfspace_cone) {
   const CoalScalar height = 1.;
   const Cone cone(radius, height);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, height / 2 - offset));
@@ -468,8 +468,8 @@ BOOST_AUTO_TEST_CASE(halfspace_cylinder) {
   const CoalScalar height = 1.;
   const Cylinder cylinder(radius, height);
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, height / 2 - offset));
@@ -577,8 +577,8 @@ BOOST_AUTO_TEST_CASE(convex_convex) {
   const Convex<Quadrilateral> box1(buildBox(halfside, halfside, halfside));
   const Convex<Quadrilateral> box2(buildBox(halfside, halfside, halfside));
 
-  const Transform3f tf1;
-  Transform3f tf2;
+  const Transform3s tf1;
+  Transform3s tf2;
   // set translation to have a collision
   const CoalScalar offset = 0.001;
   tf2.setTranslation(Vec3s(0, 0, 2 * halfside - offset));
@@ -638,8 +638,8 @@ BOOST_AUTO_TEST_CASE(edge_case_segment_segment) {
   const Vec3s expected_cp1(0, 0.5, 0);
   const Vec3s expected_cp2(0, 1, 0);
 
-  const Transform3f tf1;  // identity
-  const Transform3f tf2;  // identity
+  const Transform3s tf1;  // identity
+  const Transform3s tf2;  // identity
 
   const size_t num_max_contact = 1;
   const CollisionRequest col_req(CollisionRequestFlag::CONTACT,
@@ -804,8 +804,8 @@ BOOST_AUTO_TEST_CASE(edge_case_vertex_vertex) {
   const size_t expected_size = 1;
   const Vec3s expected_cp(0, 0, 0);
 
-  const Transform3f tf1;  // identity
-  const Transform3f tf2;  // identity
+  const Transform3s tf1;  // identity
+  const Transform3s tf2;  // identity
 
   const size_t num_max_contact = 1;
   const CollisionRequest col_req(CollisionRequestFlag::CONTACT,
@@ -966,8 +966,8 @@ BOOST_AUTO_TEST_CASE(edge_case_segment_face) {
   const Vec3s expected_cp1(0, 0, 0);
   const Vec3s expected_cp2(-0.5, 0.5, 0);
 
-  const Transform3f tf1;  // identity
-  const Transform3f tf2;  // identity
+  const Transform3s tf1;  // identity
+  const Transform3s tf2;  // identity
 
   const size_t num_max_contact = 1;
   const CollisionRequest col_req(CollisionRequestFlag::CONTACT,
diff --git a/test/convex.cpp b/test/convex.cpp
index 02507b26348cade417222241815f117c3c7cc2c3..52363b7d85505c0f0b3f799cdb08dc1b8796e05c 100644
--- a/test/convex.cpp
+++ b/test/convex.cpp
@@ -88,7 +88,7 @@ BOOST_AUTO_TEST_CASE(convex) {
 
 template <typename Sa, typename Sb>
 void compareShapeIntersection(const Sa& sa, const Sb& sb,
-                              const Transform3f& tf1, const Transform3f& tf2,
+                              const Transform3s& tf1, const Transform3s& tf2,
                               CoalScalar tol = 1e-9) {
   CollisionRequest request(CONTACT | DISTANCE_LOWER_BOUND, 1);
   CollisionResult resA, resB;
@@ -117,8 +117,8 @@ void compareShapeIntersection(const Sa& sa, const Sb& sb,
 }
 
 template <typename Sa, typename Sb>
-void compareShapeDistance(const Sa& sa, const Sb& sb, const Transform3f& tf1,
-                          const Transform3f& tf2, CoalScalar tol = 1e-9) {
+void compareShapeDistance(const Sa& sa, const Sb& sb, const Transform3s& tf1,
+                          const Transform3s& tf2, CoalScalar tol = 1e-9) {
   DistanceRequest request(true);
   DistanceResult resA, resB;
 
@@ -154,8 +154,8 @@ BOOST_AUTO_TEST_CASE(compare_convex_box) {
   Box box(l * 2, w * 2, d * 2);
   Convex<Quadrilateral> convex_box(buildBox(l, w, d));
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   tf2.setTranslation(Vec3s(3, 0, 0));
   compareShapeIntersection(box, convex_box, tf1, tf2, eps);
diff --git a/test/distance.cpp b/test/distance.cpp
index 77a35f60c78c3c0c7ce319bf195cbbc5a99b37fe..acb89251386537e41b782fcaff7c2c68aba67036 100644
--- a/test/distance.cpp
+++ b/test/distance.cpp
@@ -56,14 +56,14 @@ bool verbose = false;
 CoalScalar DELTA = 0.001;
 
 template <typename BV>
-void distance_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
+void distance_Test(const Transform3s& tf, const std::vector<Vec3s>& vertices1,
                    const std::vector<Triangle>& triangles1,
                    const std::vector<Vec3s>& vertices2,
                    const std::vector<Triangle>& triangles2,
                    SplitMethodType split_method, unsigned int qsize,
                    DistanceRes& distance_result, bool verbose = true);
 
-bool collide_Test_OBB(const Transform3f& tf,
+bool collide_Test_OBB(const Transform3s& tf,
                       const std::vector<Vec3s>& vertices1,
                       const std::vector<Triangle>& triangles1,
                       const std::vector<Vec3s>& vertices2,
@@ -71,7 +71,7 @@ bool collide_Test_OBB(const Transform3f& tf,
                       SplitMethodType split_method, bool verbose);
 
 template <typename BV, typename TraversalNode>
-void distance_Test_Oriented(const Transform3f& tf,
+void distance_Test_Oriented(const Transform3s& tf,
                             const std::vector<Vec3s>& vertices1,
                             const std::vector<Triangle>& triangles1,
                             const std::vector<Vec3s>& vertices2,
@@ -93,7 +93,7 @@ BOOST_AUTO_TEST_CASE(mesh_distance) {
   loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
   loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
 
-  std::vector<Transform3f> transforms;  // t0
+  std::vector<Transform3s> transforms;  // t0
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
 #ifndef NDEBUG  // if debug mode
   std::size_t n = 1;
@@ -468,7 +468,7 @@ BOOST_AUTO_TEST_CASE(mesh_distance) {
 }
 
 template <typename BV, typename TraversalNode>
-void distance_Test_Oriented(const Transform3f& tf,
+void distance_Test_Oriented(const Transform3s& tf,
                             const std::vector<Vec3s>& vertices1,
                             const std::vector<Triangle>& triangles1,
                             const std::vector<Vec3s>& vertices2,
@@ -491,7 +491,7 @@ void distance_Test_Oriented(const Transform3f& tf,
   DistanceResult local_result;
   TraversalNode node;
   if (!initialize(node, (const BVHModel<BV>&)m1, tf, (const BVHModel<BV>&)m2,
-                  Transform3f(), DistanceRequest(true), local_result))
+                  Transform3s(), DistanceRequest(true), local_result))
     std::cout << "initialize error" << std::endl;
 
   node.enable_statistics = verbose;
@@ -516,7 +516,7 @@ void distance_Test_Oriented(const Transform3f& tf,
 }
 
 template <typename BV>
-void distance_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
+void distance_Test(const Transform3s& tf, const std::vector<Vec3s>& vertices1,
                    const std::vector<Triangle>& triangles1,
                    const std::vector<Vec3s>& vertices2,
                    const std::vector<Triangle>& triangles2,
@@ -535,7 +535,7 @@ void distance_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
   m2.addSubModel(vertices2, triangles2);
   m2.endModel();
 
-  Transform3f pose1(tf), pose2;
+  Transform3s pose1(tf), pose2;
 
   DistanceResult local_result;
   MeshDistanceTraversalNode<BV> node;
@@ -565,7 +565,7 @@ void distance_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
   }
 }
 
-bool collide_Test_OBB(const Transform3f& tf,
+bool collide_Test_OBB(const Transform3s& tf,
                       const std::vector<Vec3s>& vertices1,
                       const std::vector<Triangle>& triangles1,
                       const std::vector<Vec3s>& vertices2,
@@ -588,7 +588,7 @@ bool collide_Test_OBB(const Transform3f& tf,
   CollisionRequest request(CONTACT | DISTANCE_LOWER_BOUND, 1);
   MeshCollisionTraversalNodeOBB node(request);
   bool success(initialize(node, (const BVHModel<OBB>&)m1, tf,
-                          (const BVHModel<OBB>&)m2, Transform3f(),
+                          (const BVHModel<OBB>&)m2, Transform3s(),
                           local_result));
   BOOST_REQUIRE(success);
 
diff --git a/test/distance_lower_bound.cpp b/test/distance_lower_bound.cpp
index 21c2f3eea20675beb0f31a9bf10ed54354b34d44..f4386597d78fc953bff332f69d11564fdd72337b 100644
--- a/test/distance_lower_bound.cpp
+++ b/test/distance_lower_bound.cpp
@@ -56,15 +56,15 @@ using coal::DistanceRequest;
 using coal::DistanceResult;
 using coal::OBBRSS;
 using coal::shared_ptr;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Triangle;
 using coal::Vec3s;
 
-bool testDistanceLowerBound(const Transform3f& tf,
+bool testDistanceLowerBound(const Transform3s& tf,
                             const CollisionGeometryPtr_t& m1,
                             const CollisionGeometryPtr_t& m2,
                             CoalScalar& distance) {
-  Transform3f pose1(tf), pose2;
+  Transform3s pose1(tf), pose2;
 
   CollisionRequest request;
 
@@ -78,9 +78,9 @@ bool testDistanceLowerBound(const Transform3f& tf,
   return result.isCollision();
 }
 
-bool testCollide(const Transform3f& tf, const CollisionGeometryPtr_t& m1,
+bool testCollide(const Transform3s& tf, const CollisionGeometryPtr_t& m1,
                  const CollisionGeometryPtr_t& m2) {
-  Transform3f pose1(tf), pose2;
+  Transform3s pose1(tf), pose2;
 
   CollisionRequest request(coal::NO_REQUEST, 1);
   request.enable_distance_lower_bound = false;
@@ -93,9 +93,9 @@ bool testCollide(const Transform3f& tf, const CollisionGeometryPtr_t& m1,
   return result.isCollision();
 }
 
-bool testDistance(const Transform3f& tf, const CollisionGeometryPtr_t& m1,
+bool testDistance(const Transform3s& tf, const CollisionGeometryPtr_t& m1,
                   const CollisionGeometryPtr_t& m2, CoalScalar& distance) {
-  Transform3f pose1(tf), pose2;
+  Transform3s pose1(tf), pose2;
 
   DistanceRequest request;
   DistanceResult result;
@@ -131,7 +131,7 @@ BOOST_AUTO_TEST_CASE(mesh_mesh) {
   m2->addSubModel(p2, t2);
   m2->endModel();
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
   std::size_t n = 100;
 
@@ -161,12 +161,12 @@ BOOST_AUTO_TEST_CASE(box_sphere) {
   shared_ptr<coal::Sphere> sphere(new coal::Sphere(0.5));
   shared_ptr<coal::Box> box(new coal::Box(1., 1., 1.));
 
-  Transform3f M1;
+  Transform3s M1;
   M1.setIdentity();
-  Transform3f M2;
+  Transform3s M2;
   M2.setIdentity();
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-2., -2., -2., 2., 2., 2.};
   const std::size_t n = 1000;
 
@@ -198,12 +198,12 @@ BOOST_AUTO_TEST_CASE(sphere_sphere) {
   shared_ptr<coal::Sphere> sphere1(new coal::Sphere(0.5));
   shared_ptr<coal::Sphere> sphere2(new coal::Sphere(1.));
 
-  Transform3f M1;
+  Transform3s M1;
   M1.setIdentity();
-  Transform3f M2;
+  Transform3s M2;
   M2.setIdentity();
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-2., -2., -2., 2., 2., 2.};
   const std::size_t n = 1000;
 
@@ -245,7 +245,7 @@ BOOST_AUTO_TEST_CASE(box_mesh) {
   m1->addSubModel(p1, t1);
   m1->endModel();
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
   std::size_t n = 100;
 
diff --git a/test/frontlist.cpp b/test/frontlist.cpp
index df1e6e6dc38b0565f428a3648da02cc82d2677ea..9e68a326ced5542fbd598c4b99125cea1e303205 100644
--- a/test/frontlist.cpp
+++ b/test/frontlist.cpp
@@ -51,7 +51,7 @@ using namespace coal;
 namespace utf = boost::unit_test::framework;
 
 template <typename BV>
-bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
+bool collide_front_list_Test(const Transform3s& tf1, const Transform3s& tf2,
                              const std::vector<Vec3s>& vertices1,
                              const std::vector<Triangle>& triangles1,
                              const std::vector<Vec3s>& vertices2,
@@ -60,8 +60,8 @@ bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
                              bool verbose);
 
 template <typename BV, typename TraversalNode>
-bool collide_front_list_Test_Oriented(const Transform3f& tf1,
-                                      const Transform3f& tf2,
+bool collide_front_list_Test_Oriented(const Transform3s& tf1,
+                                      const Transform3s& tf2,
                                       const std::vector<Vec3s>& vertices1,
                                       const std::vector<Triangle>& triangles1,
                                       const std::vector<Vec3s>& vertices2,
@@ -70,7 +70,7 @@ bool collide_front_list_Test_Oriented(const Transform3f& tf1,
                                       bool verbose);
 
 template <typename BV>
-bool collide_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
+bool collide_Test(const Transform3s& tf, const std::vector<Vec3s>& vertices1,
                   const std::vector<Triangle>& triangles1,
                   const std::vector<Vec3s>& vertices2,
                   const std::vector<Triangle>& triangles2,
@@ -84,8 +84,8 @@ BOOST_AUTO_TEST_CASE(front_list) {
   loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
   loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
 
-  std::vector<Transform3f> transforms;   // t0
-  std::vector<Transform3f> transforms2;  // t1
+  std::vector<Transform3s> transforms;   // t0
+  std::vector<Transform3s> transforms2;  // t1
   CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
   CoalScalar delta_trans[] = {1, 1, 1};
 #ifndef NDEBUG  // if debug mode
@@ -270,7 +270,7 @@ BOOST_AUTO_TEST_CASE(front_list) {
 }
 
 template <typename BV>
-bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
+bool collide_front_list_Test(const Transform3s& tf1, const Transform3s& tf2,
                              const std::vector<Vec3s>& vertices1,
                              const std::vector<Triangle>& triangles1,
                              const std::vector<Vec3s>& vertices2,
@@ -297,7 +297,7 @@ bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
   m2.addSubModel(vertices2, triangles2);
   m2.endModel();
 
-  Transform3f pose1, pose2;
+  Transform3s pose1, pose2;
 
   CollisionResult local_result;
   CollisionRequest request(NO_REQUEST, (std::numeric_limits<int>::max)());
@@ -336,8 +336,8 @@ bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2,
 }
 
 template <typename BV, typename TraversalNode>
-bool collide_front_list_Test_Oriented(const Transform3f& tf1,
-                                      const Transform3f& tf2,
+bool collide_front_list_Test_Oriented(const Transform3s& tf1,
+                                      const Transform3s& tf2,
                                       const std::vector<Vec3s>& vertices1,
                                       const std::vector<Triangle>& triangles1,
                                       const std::vector<Vec3s>& vertices2,
@@ -359,7 +359,7 @@ bool collide_front_list_Test_Oriented(const Transform3f& tf1,
   m2.addSubModel(vertices2, triangles2);
   m2.endModel();
 
-  Transform3f pose1(tf1), pose2;
+  Transform3s pose1(tf1), pose2;
 
   CollisionResult local_result;
   CollisionRequest request(NO_REQUEST, (std::numeric_limits<int>::max)());
@@ -392,7 +392,7 @@ bool collide_front_list_Test_Oriented(const Transform3f& tf1,
 }
 
 template <typename BV>
-bool collide_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
+bool collide_Test(const Transform3s& tf, const std::vector<Vec3s>& vertices1,
                   const std::vector<Triangle>& triangles1,
                   const std::vector<Vec3s>& vertices2,
                   const std::vector<Triangle>& triangles2,
@@ -410,7 +410,7 @@ bool collide_Test(const Transform3f& tf, const std::vector<Vec3s>& vertices1,
   m2.addSubModel(vertices2, triangles2);
   m2.endModel();
 
-  Transform3f pose1(tf), pose2;
+  Transform3s pose1(tf), pose2;
 
   CollisionResult local_result;
   CollisionRequest request(NO_REQUEST, (std::numeric_limits<int>::max)());
diff --git a/test/geometric_shapes.cpp b/test/geometric_shapes.cpp
index ad89819cc4bf20f54772c0adde394edf0e2cc669..ec8e6b468d06bbea835ada9f1d54cb2420969d97 100644
--- a/test/geometric_shapes.cpp
+++ b/test/geometric_shapes.cpp
@@ -78,8 +78,8 @@ std::ostream& operator<<(std::ostream& os, const Box& b) {
 
 template <typename S1, typename S2>
 void printComparisonError(const std::string& comparison_type, const S1& s1,
-                          const Transform3f& tf1, const S2& s2,
-                          const Transform3f& tf2,
+                          const Transform3s& tf1, const S2& s2,
+                          const Transform3s& tf2,
                           const Vec3s& contact_or_normal,
                           const Vec3s& expected_contact_or_normal,
                           bool check_opposite_normal, CoalScalar tol) {
@@ -109,8 +109,8 @@ void printComparisonError(const std::string& comparison_type, const S1& s1,
 
 template <typename S1, typename S2>
 void printComparisonError(const std::string& comparison_type, const S1& s1,
-                          const Transform3f& tf1, const S2& s2,
-                          const Transform3f& tf2, CoalScalar depth,
+                          const Transform3s& tf1, const S2& s2,
+                          const Transform3s& tf2, CoalScalar depth,
                           CoalScalar expected_depth, CoalScalar tol) {
   std::cout << "Disagreement between " << comparison_type << " and expected_"
             << comparison_type << " for " << getNodeTypeName(s1.getNodeType())
@@ -126,8 +126,8 @@ void printComparisonError(const std::string& comparison_type, const S1& s1,
 }
 
 template <typename S1, typename S2>
-void compareContact(const S1& s1, const Transform3f& tf1, const S2& s2,
-                    const Transform3f& tf2, const Vec3s& contact,
+void compareContact(const S1& s1, const Transform3s& tf1, const S2& s2,
+                    const Transform3s& tf2, const Vec3s& contact,
                     Vec3s* expected_point, CoalScalar depth,
                     CoalScalar* expected_depth, const Vec3s& normal,
                     Vec3s* expected_normal, bool check_opposite_normal,
@@ -162,8 +162,8 @@ void compareContact(const S1& s1, const Transform3f& tf1, const S2& s2,
 }
 
 template <typename S1, typename S2>
-void testShapeCollide(const S1& s1, const Transform3f& tf1, const S2& s2,
-                      const Transform3f& tf2, bool expect_collision,
+void testShapeCollide(const S1& s1, const Transform3s& tf1, const S2& s2,
+                      const Transform3s& tf2, bool expect_collision,
                       Vec3s* expected_point = NULL,
                       CoalScalar* expected_depth = NULL,
                       Vec3s* expected_normal = NULL,
@@ -210,85 +210,85 @@ void testShapeCollide(const S1& s1, const Transform3f& tf1, const S2& s2,
 BOOST_AUTO_TEST_CASE(box_to_bvh) {
   Box shape(1, 1, 1);
   BVHModel<OBB> bvh;
-  generateBVHModel(bvh, shape, Transform3f());
+  generateBVHModel(bvh, shape, Transform3s());
 }
 
 BOOST_AUTO_TEST_CASE(sphere_to_bvh) {
   Sphere shape(1);
   BVHModel<OBB> bvh;
-  generateBVHModel(bvh, shape, Transform3f(), 10, 10);
-  generateBVHModel(bvh, shape, Transform3f(), 50);
+  generateBVHModel(bvh, shape, Transform3s(), 10, 10);
+  generateBVHModel(bvh, shape, Transform3s(), 50);
 }
 
 BOOST_AUTO_TEST_CASE(cylinder_to_bvh) {
   Cylinder shape(1, 1);
   BVHModel<OBB> bvh;
-  generateBVHModel(bvh, shape, Transform3f(), 10, 10);
-  generateBVHModel(bvh, shape, Transform3f(), 50);
+  generateBVHModel(bvh, shape, Transform3s(), 10, 10);
+  generateBVHModel(bvh, shape, Transform3s(), 50);
 }
 
 BOOST_AUTO_TEST_CASE(cone_to_bvh) {
   Cone shape(1, 1);
   BVHModel<OBB> bvh;
-  generateBVHModel(bvh, shape, Transform3f(), 10, 10);
-  generateBVHModel(bvh, shape, Transform3f(), 50);
+  generateBVHModel(bvh, shape, Transform3s(), 10, 10);
+  generateBVHModel(bvh, shape, Transform3s(), 50);
 }
 
 BOOST_AUTO_TEST_CASE(collide_spheresphere) {
   Sphere s1(20);
   Sphere s2(10);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(40, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(40, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(40, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(40, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(30, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(30, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(30.01, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(30.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(30.01, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(30.01, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(29.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(29.9, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(29.9, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(29.9, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   normal << 1, 0, 0;  // If the centers of two sphere are at the same position,
                       // the normal is (1, 0, 0)
   SET_LINE;
@@ -301,32 +301,32 @@ BOOST_AUTO_TEST_CASE(collide_spheresphere) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-29.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-29.9, 0, 0));
   normal << -1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-29.9, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-29.9, 0, 0));
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-30.0, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-30.0, 0, 0));
   normal << -1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-30.01, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-30.01, 0, 0));
   normal << -1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-30.01, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-30.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 }
@@ -354,8 +354,8 @@ void testBoxBoxContactPoints(const Matrix3s& R) {
     vertices[i].array() *= s2.halfSide.array();
   }
 
-  Transform3f tf1 = Transform3f(Vec3s(0, 0, -50));
-  Transform3f tf2 = Transform3f(R);
+  Transform3s tf1 = Transform3s(Vec3s(0, 0, -50));
+  Transform3s tf2 = Transform3s(R);
 
   Vec3s normal;
   Vec3s p1, p2;
@@ -385,10 +385,10 @@ BOOST_AUTO_TEST_CASE(collide_boxbox) {
   Box s1(20, 40, 50);
   Box s2(10, 10, 10);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
@@ -398,8 +398,8 @@ BOOST_AUTO_TEST_CASE(collide_boxbox) {
   Quatf q;
   q = AngleAxis((CoalScalar)3.140 / 6, UnitZ);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // 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;
@@ -414,37 +414,37 @@ BOOST_AUTO_TEST_CASE(collide_boxbox) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(15, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(15, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, 1e-8);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(15.01, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(15.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(15.01, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(15.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(q);
+  tf1 = Transform3s();
+  tf2 = Transform3s(q);
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(q);
+  tf2 = transform * Transform3s(q);
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, 0x0);
 
   int numTests = 100;
   for (int i = 0; i < numTests; ++i) {
-    Transform3f tf;
+    Transform3s tf;
     generateRandomTransform(extents, tf);
     SET_LINE;
     testBoxBoxContactPoints(tf.getRotation());
@@ -455,18 +455,18 @@ BOOST_AUTO_TEST_CASE(collide_spherebox) {
   Sphere s1(20);
   Box s2(5, 5, 5);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // 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;
@@ -480,24 +480,24 @@ BOOST_AUTO_TEST_CASE(collide_spherebox) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(22.50001, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(22.50001, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(22.501, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(22.501, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(22.4, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(22.4, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(22.4, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(22.4, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
@@ -516,8 +516,8 @@ BOOST_AUTO_TEST_CASE(distance_spherebox) {
   coal::Box box(10, 2, 10);
 
   coal::DistanceResult result;
-  distance(&sphere, Transform3f(rotSphere, trSphere), &box,
-           Transform3f(rotBox, trBox), DistanceRequest(true), result);
+  distance(&sphere, Transform3s(rotSphere, trSphere), &box,
+           Transform3s(rotBox, trBox), DistanceRequest(true), result);
 
   CoalScalar eps = Eigen::NumTraits<CoalScalar>::epsilon();
   BOOST_CHECK_CLOSE(result.min_distance, 3., eps);
@@ -530,18 +530,18 @@ BOOST_AUTO_TEST_CASE(collide_spherecapsule) {
   Sphere s1(20);
   Capsule s2(5, 10);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // TODO: Need convention for normal when the centers of two objects are at
   // same position.
   SET_LINE;
@@ -554,38 +554,38 @@ BOOST_AUTO_TEST_CASE(collide_spherecapsule) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(24.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(24.9, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(24.9, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(24.9, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(25, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(25, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(24.999999, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(24.999999, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(25.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(25.1, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(25.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(25.1, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
@@ -595,18 +595,18 @@ BOOST_AUTO_TEST_CASE(collide_cylindercylinder) {
   Cylinder s1(5, 15);
   Cylinder s2(5, 15);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // TODO: Need convention for normal when the centers of two objects are at
   // same position.
   SET_LINE;
@@ -619,37 +619,37 @@ BOOST_AUTO_TEST_CASE(collide_cylindercylinder) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(9.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(9.9, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 9.9, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 9.9, 0));
   normal << 0, 1, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(9.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(9.9, 0, 0));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(9.9, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(9.9, 0, 0));
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.01, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10.01, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 }
@@ -658,18 +658,18 @@ BOOST_AUTO_TEST_CASE(collide_conecone) {
   Cone s1(5, 10);
   Cone s2(5, 10);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // TODO: Need convention for normal when the centers of two objects are at
   // same position.
   SET_LINE;
@@ -682,9 +682,9 @@ BOOST_AUTO_TEST_CASE(collide_conecone) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
+  tf1 = Transform3s();
   // z=0 is a singular points. Two normals could be returned.
-  tf2 = Transform3f(Vec3s(9.9, 0, 0.00001));
+  tf2 = Transform3s(Vec3s(9.9, 0, 0.00001));
   normal = Vec3s(2 * (s1.halfLength + s2.halfLength), 0, s1.radius + s2.radius)
                .normalized();
   SET_LINE;
@@ -697,36 +697,36 @@ BOOST_AUTO_TEST_CASE(collide_conecone) {
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(9.9, 0, 0.00001));
+  tf2 = transform * Transform3s(Vec3s(9.9, 0, 0.00001));
   normal = Vec3s(2 * (s1.halfLength + s2.halfLength), 0, s1.radius + s2.radius)
                .normalized();
   normal = transform.getRotation() * normal;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, true, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.001, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.001, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10.001, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10.001, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 9.9));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 9.9));
   normal << 0, 0, 1;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 9.9));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 9.9));
   normal = transform.getRotation() * Vec3s(0, 0, 1);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
@@ -736,18 +736,18 @@ BOOST_AUTO_TEST_CASE(collide_conecylinder) {
   Cylinder s1(5, 10);
   Cone s2(5, 10);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   // Vec3s point;
   // CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   // TODO: Need convention for normal when the centers of two objects are at
   // same position.
   SET_LINE;
@@ -760,8 +760,8 @@ BOOST_AUTO_TEST_CASE(collide_conecylinder) {
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(9.9, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(9.9, 0, 0));
   normal =
       Vec3s(2 * (s1.halfLength + s2.halfLength), 0, -(s1.radius + s2.radius))
           .normalized();
@@ -769,73 +769,73 @@ BOOST_AUTO_TEST_CASE(collide_conecylinder) {
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(9.9, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(9.9, 0, 0));
   normal = transform.getRotation() * normal;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(9.9, 0, 0.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(9.9, 0, 0.1));
   normal << 1, 0, 0;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(9.9, 0, 0.1));
+  tf2 = transform * Transform3s(Vec3s(9.9, 0, 0.1));
   normal = transform.getRotation() * normal;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.01, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10.01, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10.01, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10, 0, 0));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, NULL);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 9.9));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 9.9));
   normal << 0, 0, 1;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 9.9));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 9.9));
   normal = transform.getRotation() * Vec3s(0, 0, 1);
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10.01));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10.01));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.01));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.01));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10));
   normal << 0, 0, 1;
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, true, NULL, NULL, &normal, false, tol_gjk);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s1, tf1, s2, tf2, false);
 }
@@ -843,7 +843,7 @@ BOOST_AUTO_TEST_CASE(collide_conecylinder) {
 BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
   Sphere s(10);
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s normal;
@@ -857,12 +857,12 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << -20, 0, 0;
     t[2] << 0, 20, 0;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();  // identity
+    Transform3s tf_tri = Transform3s();  // identity
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.001));
     normal << 0, 0, 1;
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -871,7 +871,7 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     tf_tri.setTranslation(Vec3s(0, 0, -0.001));
     normal << 0, 0, -1;
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -884,13 +884,13 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << 9.9, -20, 0;
     t[2] << 9.9, 20, 0;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.001));
     normal << 9.9, 0, 0.001;
     normal.normalize();
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -900,7 +900,7 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     normal << 9.9, 0, -0.001;
     normal.normalize();
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -913,12 +913,12 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << -20, 0, 0;
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0, 0.001, 0));
     normal << 0, 1, 0;
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -927,7 +927,7 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     tf_tri.setTranslation(Vec3s(0, -0.001, 0));
     normal << 0, -1, 0;
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -940,12 +940,12 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << 0, -10, 0;
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0.001, 0, 0));
     normal << 1, 0, 0;
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -953,7 +953,7 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
 
     tf_tri.setTranslation(Vec3s(-0.001, 0, 0));
     normal << -1, 0, 0;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     SET_LINE;
     normal = transform.getRotation() * normal;
     SET_LINE;
@@ -970,17 +970,17 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << -20, 0, 0;
     t[2] << 0, 20, 0;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0, 0, 10.1));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(0, 0, -10.1));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
   }
@@ -992,16 +992,16 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
 
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
     tf_tri.setTranslation(Vec3s(0, 10.1, 0));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(0, -10.1, 0));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
   }
@@ -1012,17 +1012,17 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
     t[1] << 0, -20, 0;
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(10.1, 0, 0));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(-10.1, 0, 0));
     SET_LINE;
-    testShapeCollide(s, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(s, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(s, transform, tri, transform * tf_tri, false);
   }
@@ -1031,7 +1031,7 @@ BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
 BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
   Halfspace hs(Vec3s(0, 0, 1), 0);
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s normal;
@@ -1044,12 +1044,12 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
     t[1] << -20, 0, 0;
     t[2] << 0, 20, 0;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();  // identity
+    Transform3s tf_tri = Transform3s();  // identity
 
     tf_tri.setTranslation(Vec3s(0, 0, -0.001));
     normal = hs.n;
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1057,19 +1057,19 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(1, 1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(-1, -1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
   }
@@ -1080,12 +1080,12 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
     t[1] << -20, 0, 0;
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0, 0, -0.001));
     normal = hs.n;
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1093,19 +1093,19 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(1, 1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(-1, -1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
   }
@@ -1116,12 +1116,12 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
     t[1] << 0, -10, 0;
     t[2] << 0, 0, 20;
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();
+    Transform3s tf_tri = Transform3s();
 
     tf_tri.setTranslation(Vec3s(0, 0, -0.001));
     normal = hs.n;
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1129,26 +1129,26 @@ BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(1, 1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(-1, -1, 0.001));
     SET_LINE;
-    testShapeCollide(hs, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(hs, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(hs, transform, tri, transform * tf_tri, false);
   }
 }
 
 BOOST_AUTO_TEST_CASE(collide_planetriangle) {
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s normal;
@@ -1161,10 +1161,10 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     Plane pl(Vec3s(0, 0, 1), 0);
 
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();  // identity
+    Transform3s tf_tri = Transform3s();  // identity
     normal = -pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1173,7 +1173,7 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     tf_tri.setTranslation(Vec3s(0, 0, 0.05));
     normal = pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1181,13 +1181,13 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
 
     tf_tri.setTranslation(Vec3s(0, 0, -0.06));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(0, 0, 0.11));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
   }
@@ -1200,10 +1200,10 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     Plane pl(Vec3s(0, 1, 0), 0);
 
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();  // identity
+    Transform3s tf_tri = Transform3s();  // identity
     normal = -pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1212,7 +1212,7 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     tf_tri.setTranslation(Vec3s(0, 0.05, 0));
     normal = pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1220,13 +1220,13 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
 
     tf_tri.setTranslation(Vec3s(0, -0.06, 0));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(0, 0.11, 0));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
   }
@@ -1239,10 +1239,10 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     Plane pl(Vec3s(1, 0, 0), 0);
 
     TriangleP tri(t[0], t[1], t[2]);
-    Transform3f tf_tri = Transform3f();  // identity
+    Transform3s tf_tri = Transform3s();  // identity
     normal = -pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1251,7 +1251,7 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
     tf_tri.setTranslation(Vec3s(0.05, 0, 0));
     normal = pl.n;
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, true, NULL, NULL, &normal);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, true, NULL, NULL, &normal);
     normal = transform.getRotation() * normal;
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, true, NULL, NULL,
@@ -1259,13 +1259,13 @@ BOOST_AUTO_TEST_CASE(collide_planetriangle) {
 
     tf_tri.setTranslation(Vec3s(-0.06, 0, 0));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
 
     tf_tri.setTranslation(Vec3s(0.11, 0, 0));
     SET_LINE;
-    testShapeCollide(pl, Transform3f(), tri, tf_tri, false);
+    testShapeCollide(pl, Transform3s(), tri, tf_tri, false);
     SET_LINE;
     testShapeCollide(pl, transform, tri, transform * tf_tri, false);
   }
@@ -1275,18 +1275,18 @@ BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
   Sphere s(10);
   Halfspace hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << -5, 0, 0;
   depth = -10;
   normal << -1, 0, 0;
@@ -1301,8 +1301,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5, 0, 0));
   contact << -2.5, 0, 0;
   depth = -15;
   normal << -1, 0, 0;
@@ -1310,15 +1310,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5, 0, 0));
   contact = transform.transform(Vec3s(-2.5, 0, 0));
   depth = -15;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5, 0, 0));
   contact << -7.5, 0, 0;
   depth = -5;
   normal << -1, 0, 0;
@@ -1326,25 +1326,25 @@ BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5, 0, 0));
   contact = transform.transform(Vec3s(-7.5, 0, 0));
   depth = -5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-10.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-10.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = -20.1;
   normal << -1, 0, 0;
@@ -1352,7 +1352,7 @@ BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10.1, 0, 0));
   contact = transform.transform(Vec3s(0.05, 0, 0));
   depth = -20.1;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
@@ -1364,10 +1364,10 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   Sphere s(10);
   Plane hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
@@ -1376,8 +1376,8 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   Vec3s p1, p2;
 
   CoalScalar eps = 1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   depth = -10 + eps;
   p1 << -10 + eps, 0, 0;
   p2 << 0, 0, 0;
@@ -1395,8 +1395,8 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   depth = -10 - eps;
   p1 << 10 + eps, 0, 0;
   p2 << 0, 0, 0;
@@ -1412,8 +1412,8 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5, 0, 0));
   p1 << 10, 0, 0;
   p2 << 5, 0, 0;
   contact << (p1 + p2) / 2;
@@ -1423,15 +1423,15 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -5;
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5, 0, 0));
   p1 << -10, 0, 0;
   p2 << -5, 0, 0;
   contact << (p1 + p2) / 2;
@@ -1441,30 +1441,30 @@ BOOST_AUTO_TEST_CASE(collide_planesphere) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-10.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-10.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(10.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(10.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(10.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -1473,18 +1473,18 @@ BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
   Box s(5, 10, 20);
   Halfspace hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << -1.25, 0, 0;
   depth = -2.5;
   normal << -1, 0, 0;
@@ -1499,8 +1499,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(1.25, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(1.25, 0, 0));
   contact << -0.625, 0, 0;
   depth = -3.75;
   normal << -1, 0, 0;
@@ -1508,15 +1508,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(1.25, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(1.25, 0, 0));
   contact = transform.transform(Vec3s(-0.625, 0, 0));
   depth = -3.75;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-1.25, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-1.25, 0, 0));
   contact << -1.875, 0, 0;
   depth = -1.25;
   normal << -1, 0, 0;
@@ -1524,15 +1524,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-1.25, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-1.25, 0, 0));
   contact = transform.transform(Vec3s(-1.875, 0, 0));
   depth = -1.25;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.51, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.51, 0, 0));
   contact << 0.005, 0, 0;
   depth = -5.01;
   normal << -1, 0, 0;
@@ -1540,25 +1540,25 @@ BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.51, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.51, 0, 0));
   contact = transform.transform(Vec3s(0.005, 0, 0));
   depth = -5.01;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.51, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.51, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f(transform.getRotation());
-  tf2 = Transform3f();
+  tf1 = Transform3s(transform.getRotation());
+  tf2 = Transform3s();
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true);
 }
@@ -1567,18 +1567,18 @@ BOOST_AUTO_TEST_CASE(collide_planebox) {
   Box s(5, 10, 20);
   Plane hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   Vec3s p1(2.5, 0, 0);
   Vec3s p2(0, 0, 0);
   contact << (p1 + p2) / 2;
@@ -1595,8 +1595,8 @@ BOOST_AUTO_TEST_CASE(collide_planebox) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(1.25, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(1.25, 0, 0));
   p2 << 1.25, 0, 0;
   contact << (p1 + p2) / 2;
   depth = -1.25;
@@ -1605,15 +1605,15 @@ BOOST_AUTO_TEST_CASE(collide_planebox) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(1.25, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(1.25, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -1.25;
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-1.25, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-1.25, 0, 0));
   p1 << -2.5, 0, 0;
   p2 << -1.25, 0, 0;
   contact << (p1 + p2) / 2;
@@ -1623,35 +1623,35 @@ BOOST_AUTO_TEST_CASE(collide_planebox) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-1.25, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-1.25, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -1.25;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.51, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.51, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.51, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.51, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.51, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f(transform.getRotation());
-  tf2 = Transform3f();
+  tf1 = Transform3s(transform.getRotation());
+  tf2 = Transform3s();
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true);
 }
@@ -1660,18 +1660,18 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   Capsule s(5, 10);
   Halfspace hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << -2.5, 0, 0;
   depth = -5;
   normal << -1, 0, 0;
@@ -1686,8 +1686,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   contact << -1.25, 0, 0;
   depth = -7.5;
   normal << -1, 0, 0;
@@ -1695,15 +1695,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform(Vec3s(-1.25, 0, 0));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   contact << -3.75, 0, 0;
   depth = -2.5;
   normal << -1, 0, 0;
@@ -1711,15 +1711,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform(Vec3s(-3.75, 0, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = -10.1;
   normal << -1, 0, 0;
@@ -1727,27 +1727,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   contact = transform.transform(Vec3s(0.05, 0, 0));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 1, 0), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, -2.5, 0;
   depth = -5;
   normal << 0, -1, 0;
@@ -1762,8 +1762,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   contact << 0, -1.25, 0;
   depth = -7.5;
   normal << 0, -1, 0;
@@ -1771,15 +1771,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform(Vec3s(0, -1.25, 0));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   contact << 0, -3.75, 0;
   depth = -2.5;
   normal << 0, -1, 0;
@@ -1787,15 +1787,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform(Vec3s(0, -3.75, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   contact << 0, 0.05, 0;
   depth = -10.1;
   normal << 0, -1, 0;
@@ -1803,27 +1803,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   contact = transform.transform(Vec3s(0, 0.05, 0));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 0, 1), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, -5;
   depth = -10;
   normal << 0, 0, -1;
@@ -1838,8 +1838,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   contact << 0, 0, -3.75;
   depth = -12.5;
   normal << 0, 0, -1;
@@ -1847,15 +1847,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform(Vec3s(0, 0, -3.75));
   depth = -12.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   contact << 0, 0, -6.25;
   depth = -7.5;
   normal << 0, 0, -1;
@@ -1863,15 +1863,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform(Vec3s(0, 0, -6.25));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10.1));
   contact << 0, 0, 0.05;
   depth = -20.1;
   normal << 0, 0, -1;
@@ -1879,20 +1879,20 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.1));
   contact = transform.transform(Vec3s(0, 0, 0.05));
   depth = -20.1;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -1901,18 +1901,18 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   Capsule s(5, 10);
   Plane hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, 0;
   depth = -5;
   normal << 1, 0, 0;  // (1, 0, 0) or (-1, 0, 0)
@@ -1927,8 +1927,8 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, 0x0, 0x0, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   contact << 2.5, 0, 0;
   depth = -2.5;
   normal << 1, 0, 0;
@@ -1936,15 +1936,15 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform(Vec3s(2.5, 0, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   contact << -2.5, 0, 0;
   depth = -2.5;
   normal << -1, 0, 0;
@@ -1952,37 +1952,37 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform(Vec3s(-2.5, 0, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 1, 0), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, 0;
   depth = -5;
   normal << 0, 1, 0;  // (0, 1, 0) or (0, -1, 0)
@@ -1997,8 +1997,8 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   contact << 0, 2.5, 0;
   depth = -2.5;
   normal << 0, 1, 0;
@@ -2006,15 +2006,15 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform(Vec3s(0, 2.5, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   contact << 0, -2.5, 0;
   depth = -2.5;
   normal << 0, -1, 0;
@@ -2022,37 +2022,37 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform(Vec3s(0, -2.5, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 0, 1), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, 0;
   depth = -10;
   normal << 0, 0, 1;  // (0, 0, 1) or (0, 0, -1)
@@ -2067,8 +2067,8 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   contact << 0, 0, 2.5;
   depth = -7.5;
   normal << 0, 0, 1;
@@ -2076,15 +2076,15 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform(Vec3s(0, 0, 2.5));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, 0, 1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   contact << 0, 0, -2.5;
   depth = -7.5;
   normal << 0, 0, -1;
@@ -2092,30 +2092,30 @@ BOOST_AUTO_TEST_CASE(collide_planecapsule) {
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform(Vec3s(0, 0, -2.5));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, 0x0, &depth, 0x0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -2124,18 +2124,18 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   Cylinder s(5, 10);
   Halfspace hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << -2.5, 0, 0;
   depth = -5;
   normal << -1, 0, 0;
@@ -2150,8 +2150,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   contact << -1.25, 0, 0;
   depth = -7.5;
   normal << -1, 0, 0;
@@ -2159,15 +2159,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform(Vec3s(-1.25, 0, 0));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   contact << -3.75, 0, 0;
   depth = -2.5;
   normal << -1, 0, 0;
@@ -2175,15 +2175,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform(Vec3s(-3.75, 0, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   contact << 0.05, 0, 0;
   depth = -10.1;
   normal << -1, 0, 0;
@@ -2191,27 +2191,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   contact = transform.transform(Vec3s(0.05, 0, 0));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 1, 0), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, -2.5, 0;
   depth = -5;
   normal << 0, -1, 0;
@@ -2226,8 +2226,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   contact << 0, -1.25, 0;
   depth = -7.5;
   normal << 0, -1, 0;
@@ -2235,15 +2235,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform(Vec3s(0, -1.25, 0));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   contact << 0, -3.75, 0;
   depth = -2.5;
   normal << 0, -1, 0;
@@ -2251,15 +2251,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform(Vec3s(0, -3.75, 0));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   contact << 0, 0.05, 0;
   depth = -10.1;
   normal << 0, -1, 0;
@@ -2267,27 +2267,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   contact = transform.transform(Vec3s(0, 0.05, 0));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 0, 1), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, -2.5;
   depth = -5;
   normal << 0, 0, -1;
@@ -2302,8 +2302,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   contact << 0, 0, -1.25;
   depth = -7.5;
   normal << 0, 0, -1;
@@ -2311,15 +2311,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform(Vec3s(0, 0, -1.25));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   contact << 0, 0, -3.75;
   depth = -2.5;
   normal << 0, 0, -1;
@@ -2327,15 +2327,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform(Vec3s(0, 0, -3.75));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 5.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 5.1));
   contact << 0, 0, 0.05;
   depth = -10.1;
   normal << 0, 0, -1;
@@ -2343,20 +2343,20 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 5.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 5.1));
   contact = transform.transform(Vec3s(0, 0, 0.05));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -5.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -5.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -5.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -5.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -2365,10 +2365,10 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   Cylinder s(5, 10);
   Plane hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
@@ -2377,8 +2377,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   Vec3s p1, p2;
 
   CoalScalar eps = 1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   p1 << -5 + eps, 0, 0;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2397,8 +2397,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   p1 << 5 + eps, 0, 0;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2416,8 +2416,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   p1 << 5, 0, 0;
   p2 << 2.5, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2427,15 +2427,15 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   p1 << -5, 0, 0;
   p2 << -2.5, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2445,38 +2445,38 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 1, 0), 0);
 
   eps = 1e-6;
-  tf1 = Transform3f(Vec3s(0, eps, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, eps, 0));
+  tf2 = Transform3s();
   p1 << 0, -5 + eps, 0;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2494,8 +2494,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(0, eps, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, eps, 0));
+  tf2 = Transform3s();
   p1 << 0, 5 + eps, 0;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2512,8 +2512,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   p1 << 0, 5, 0;
   p2 << 0, 2.5, 0;
   contact << (p1 + p2) / 2;
@@ -2523,15 +2523,15 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   p1 << 0, -5, 0;
   p2 << 0, -2.5, 0;
   contact << (p1 + p2) / 2;
@@ -2541,38 +2541,38 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 0, 1), 0);
 
   eps = 1e-6;
-  tf1 = Transform3f(Vec3s(0, 0, eps));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, 0, eps));
+  tf2 = Transform3s();
   p1 << 0, 0, -5 + eps;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2590,8 +2590,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(0, 0, eps));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, 0, eps));
+  tf2 = Transform3s();
   p1 << 0, 0, 5 + eps;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -2608,8 +2608,8 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   p1 << 0, 0, 5;
   p2 << 0, 0, 2.5;
   contact << (p1 + p2) / 2;
@@ -2619,15 +2619,15 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, 1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   p1 << 0, 0, -5.;
   p2 << 0, 0, -2.5;
   contact << (p1 + p2) / 2;
@@ -2637,30 +2637,30 @@ BOOST_AUTO_TEST_CASE(collide_planecylinder) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -2669,18 +2669,18 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   Cone s(5, 10);
   Halfspace hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
   CoalScalar depth;
   Vec3s normal;
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << -2.5, 0, -5;
   depth = -5;
   normal << -1, 0, 0;
@@ -2695,8 +2695,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   contact << -1.25, 0, -5;
   depth = -7.5;
   normal << -1, 0, 0;
@@ -2704,15 +2704,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform(Vec3s(-1.25, 0, -5));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   contact << -3.75, 0, -5;
   depth = -2.5;
   normal << -1, 0, 0;
@@ -2720,15 +2720,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform(Vec3s(-3.75, 0, -5));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   contact << 0.05, 0, -5;
   depth = -10.1;
   normal << -1, 0, 0;
@@ -2736,27 +2736,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   contact = transform.transform(Vec3s(0.05, 0, -5));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 1, 0), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, -2.5, -5;
   depth = -5;
   normal << 0, -1, 0;
@@ -2771,8 +2771,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   contact << 0, -1.25, -5;
   depth = -7.5;
   normal << 0, -1, 0;
@@ -2780,15 +2780,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform(Vec3s(0, -1.25, -5));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   contact << 0, -3.75, -5;
   depth = -2.5;
   normal << 0, -1, 0;
@@ -2796,15 +2796,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform(Vec3s(0, -3.75, -5));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   contact << 0, 0.05, -5;
   depth = -10.1;
   normal << 0, -1, 0;
@@ -2812,27 +2812,27 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   contact = transform.transform(Vec3s(0, 0.05, -5));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Halfspace(Vec3s(0, 0, 1), 0);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f();
+  tf1 = Transform3s();
+  tf2 = Transform3s();
   contact << 0, 0, -2.5;
   depth = -5;
   normal << 0, 0, -1;
@@ -2847,8 +2847,8 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   contact << 0, 0, -1.25;
   depth = -7.5;
   normal << 0, 0, -1;
@@ -2856,15 +2856,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform(Vec3s(0, 0, -1.25));
   depth = -7.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   contact << 0, 0, -3.75;
   depth = -2.5;
   normal << 0, 0, -1;
@@ -2872,15 +2872,15 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform(Vec3s(0, 0, -3.75));
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 5.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 5.1));
   contact << 0, 0, 0.05;
   depth = -10.1;
   normal << 0, 0, -1;
@@ -2888,20 +2888,20 @@ BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 5.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 5.1));
   contact = transform.transform(Vec3s(0, 0, 0.05));
   depth = -10.1;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -5.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -5.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -5.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -5.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
@@ -2910,10 +2910,10 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   Cone s(5, 10);
   Plane hs(Vec3s(1, 0, 0), 0);
 
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   Vec3s contact;
@@ -2922,8 +2922,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   Vec3s p1, p2;
 
   CoalScalar eps = 1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   p1 << -5 + eps, 0, -5;
   p2 << 0, 0, -5;
   contact << (p1 + p2) / 2;
@@ -2942,8 +2942,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(eps, 0, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(eps, 0, 0));
+  tf2 = Transform3s();
   p1 << 5 + eps, 0, -5;
   p2 << 0, 0, -5;
   contact << (p1 + p2) / 2;
@@ -2961,8 +2961,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(2.5, 0, 0));
   p1 << 5, 0, -5;
   p2 << 2.5, 0, -5;
   contact << (p1 + p2) / 2;
@@ -2972,15 +2972,15 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(2.5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-2.5, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-2.5, 0, 0));
   p1 << -5, 0, -5;
   p2 << -2.5, 0, -5;
   contact << (p1 + p2) / 2;
@@ -2990,38 +2990,38 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-2.5, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-2.5, 0, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(-1, 0, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(-5.1, 0, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(-5.1, 0, 0));
+  tf2 = transform * Transform3s(Vec3s(-5.1, 0, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 1, 0), 0);
 
   eps = 1e-6;
-  tf1 = Transform3f(Vec3s(0, eps, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, eps, 0));
+  tf2 = Transform3s();
   p1 << 0, -5 + eps, -5;
   p2 << 0, 0, -5;
   contact << (p1 + p2) / 2;
@@ -3039,8 +3039,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(0, eps, 0));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, eps, 0));
+  tf2 = Transform3s();
   p1 << 0, 5 + eps, -5;
   p2 << 0, 0, -5;
   contact << (p1 + p2) / 2;
@@ -3057,8 +3057,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 2.5, 0));
   p1 << 0, 5, -5;
   p2 << 0, 2.5, -5;
   contact << (p1 + p2) / 2;
@@ -3068,15 +3068,15 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 2.5, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -2.5, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -2.5, 0));
   p1 << 0, -5, -5;
   p2 << 0, -2.5, -5;
   contact << (p1 + p2) / 2;
@@ -3086,38 +3086,38 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -2.5, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -2.5, 0));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, -1, 0);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, 5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, -5.1, 0));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, -5.1, 0));
+  tf2 = transform * Transform3s(Vec3s(0, -5.1, 0));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   hs = Plane(Vec3s(0, 0, 1), 0);
 
   eps = 1e-6;
-  tf1 = Transform3f(Vec3s(0, 0, eps));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, 0, eps));
+  tf2 = Transform3s();
   p1 << 0, 0, -5 + eps;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -3135,8 +3135,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
   eps = -1e-6;
-  tf1 = Transform3f(Vec3s(0, 0, eps));
-  tf2 = Transform3f();
+  tf1 = Transform3s(Vec3s(0, 0, eps));
+  tf2 = Transform3s();
   p1 << 0, 0, 5 + eps;
   p2 << 0, 0, 0;
   contact << (p1 + p2) / 2;
@@ -3153,8 +3153,8 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal, true);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 2.5));
   p1 << 0, 0, 5;
   p2 << 0, 0, 2.5;
   contact << (p1 + p2) / 2;
@@ -3164,15 +3164,15 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 2.5));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, 1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -2.5));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -2.5));
   p1 << 0, 0, -5;
   p2 << 0, 0, -2.5;
   contact << (p1 + p2) / 2;
@@ -3182,43 +3182,43 @@ BOOST_AUTO_TEST_CASE(collide_planecone) {
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -2.5));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -2.5));
   contact = transform.transform((p1 + p2) / 2);
   depth = -2.5;
   normal = transform.getRotation() * Vec3s(0, 0, -1);
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, true, &contact, &depth, &normal);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, 10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, 10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, 10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
-  tf1 = Transform3f();
-  tf2 = Transform3f(Vec3s(0, 0, -10.1));
+  tf1 = Transform3s();
+  tf2 = Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 
   tf1 = transform;
-  tf2 = transform * Transform3f(Vec3s(0, 0, -10.1));
+  tf2 = transform * Transform3s(Vec3s(0, 0, -10.1));
   SET_LINE;
   testShapeCollide(s, tf1, hs, tf2, false);
 }
 
 BOOST_AUTO_TEST_CASE(collide_planeplane) {
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   Vec3s normal;
   Vec3s contact;
   CoalScalar distance;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   {
@@ -3331,14 +3331,14 @@ BOOST_AUTO_TEST_CASE(collide_planeplane) {
 }
 
 BOOST_AUTO_TEST_CASE(collide_halfspacehalfspace) {
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   Vec3s normal;
   Vec3s contact;
   CoalScalar distance;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   {
@@ -3447,14 +3447,14 @@ BOOST_AUTO_TEST_CASE(collide_halfspacehalfspace) {
 }
 
 BOOST_AUTO_TEST_CASE(collide_halfspaceplane) {
-  Transform3f tf1;
-  Transform3f tf2;
+  Transform3s tf1;
+  Transform3s tf2;
 
   Vec3s normal;
   Vec3s contact;
   CoalScalar distance;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   {
@@ -3570,67 +3570,67 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_spheresphere) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist = -1;
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(40, 0, 0)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(40, 0, 0)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(30.1, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(30.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(29.9, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(29.9, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(dist <= 0);
 
-  dist = solver1.shapeDistance(s1, Transform3f(Vec3s(40, 0, 0)), s2,
-                               Transform3f(), compute_penetration, closest_p1,
+  dist = solver1.shapeDistance(s1, Transform3s(Vec3s(40, 0, 0)), s2,
+                               Transform3s(), compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10) < 0.001);
 
-  dist = solver1.shapeDistance(s1, Transform3f(Vec3s(30.1, 0, 0)), s2,
-                               Transform3f(), compute_penetration, closest_p1,
+  dist = solver1.shapeDistance(s1, Transform3s(Vec3s(30.1, 0, 0)), s2,
+                               Transform3s(), compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
-  dist = solver1.shapeDistance(s1, Transform3f(Vec3s(29.9, 0, 0)), s2,
-                               Transform3f(), compute_penetration, closest_p1,
+  dist = solver1.shapeDistance(s1, Transform3s(Vec3s(29.9, 0, 0)), s2,
+                               Transform3s(), compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(dist < 0);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(40, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(40, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(30.1, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(30.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(29.9, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(29.9, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(dist < 0);
 
-  dist = solver1.shapeDistance(s1, transform * Transform3f(Vec3s(40, 0, 0)), s2,
+  dist = solver1.shapeDistance(s1, transform * Transform3s(Vec3s(40, 0, 0)), s2,
                                transform, compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10) < 0.001);
 
-  dist = solver1.shapeDistance(s1, transform * Transform3f(Vec3s(30.1, 0, 0)),
+  dist = solver1.shapeDistance(s1, transform * Transform3s(Vec3s(30.1, 0, 0)),
                                s2, transform, compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
-  dist = solver1.shapeDistance(s1, transform * Transform3f(Vec3s(29.9, 0, 0)),
+  dist = solver1.shapeDistance(s1, transform * Transform3s(Vec3s(29.9, 0, 0)),
                                s2, transform, compute_penetration, closest_p1,
                                closest_p2, normal);
   BOOST_CHECK(dist < 0);
@@ -3642,12 +3642,12 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxbox) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist;
 
-  dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+  dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                compute_penetration, closest_p1, closest_p2,
                                normal);
   BOOST_CHECK(dist <= 0);
@@ -3658,57 +3658,57 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxbox) {
   BOOST_CHECK(dist <= 0);
 
   dist = solver1.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(10.1, 0, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(20.1, 0, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(20.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(0, 20.2, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(0, 20.2, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10.2) < 0.001);
 
   dist = solver1.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(10.1, 10.1, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(10.1, 10.1, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1 * 1.414) < 0.001);
 
   dist = solver2.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(10.1, 0, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver2.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(20.1, 0, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(20.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10.1) < 0.001);
 
   dist = solver2.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(0, 20.1, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(0, 20.1, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 10.1) < 0.001);
 
   dist = solver2.shapeDistance(
-      s2, Transform3f(), s2, Transform3f(Vec3s(10.1, 10.1, 0)),
+      s2, Transform3s(), s2, Transform3s(Vec3s(10.1, 10.1, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1 * 1.414) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(15.1, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(15.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(20, 0, 0)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(20, 0, 0)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 5) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(20, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(20, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 5) < 0.001);
 }
@@ -3717,12 +3717,12 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylinderbox) {
   Cylinder s1(0.029, 0.1);
   Box s2(1.6, 0.6, 0.025);
 
-  Transform3f tf1(
+  Transform3s tf1(
       Quatf(0.5279170511703305, -0.50981118132505521, -0.67596178682051911,
             0.0668715876735793),
       Vec3s(0.041218354748013122, 1.2022554710435607, 0.77338855025700015));
 
-  Transform3f tf2(
+  Transform3s tf2(
       Quatf(0.70738826916719977, 0, 0, 0.70682518110536596),
       Vec3s(-0.29936284351096382, 0.80023864435868775, 0.71750000000000003));
 
@@ -3771,7 +3771,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxsphere) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist;
@@ -3779,8 +3779,8 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxsphere) {
   int N = 10;
   for (int i = 0; i < N + 1; ++i) {
     CoalScalar dbox = 0.0001 + (s1.radius + s2.halfSide(0)) * i * 4 / (3 * N);
-    dist = solver1.shapeDistance(s1, Transform3f(Vec3s(dbox, 0., 0.)), s2,
-                                 Transform3f(), compute_penetration, closest_p1,
+    dist = solver1.shapeDistance(s1, Transform3s(Vec3s(dbox, 0., 0.)), s2,
+                                 Transform3s(), compute_penetration, closest_p1,
                                  closest_p2, normal);
     BOOST_CHECK_CLOSE(dist, (dbox - s1.radius - s2.halfSide(0)), 1e-6);
     EIGEN_VECTOR_IS_APPROX(normal, -Vec3s(1, 0, 0), 1e-6);
@@ -3789,13 +3789,13 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxsphere) {
         solver1.shapeDistance(s1, transform, s2, transform, compute_penetration,
                               closest_p1, closest_p2, normal);
     dist = solver1.shapeDistance(
-        s1, transform * Transform3f(Vec3s(dbox, 0., 0.)), s2, transform,
+        s1, transform * Transform3s(Vec3s(dbox, 0., 0.)), s2, transform,
         compute_penetration, closest_p1, closest_p2, normal);
     BOOST_CHECK_CLOSE(dist, (dbox - s1.radius - s2.halfSide(0)), 1e-6);
     EIGEN_VECTOR_IS_APPROX(normal, -transform.getRotation().col(0), 1e-6);
   }
 
-  dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+  dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                compute_penetration, closest_p1, closest_p2,
                                normal);
   BOOST_CHECK(dist <= 0);
@@ -3806,22 +3806,22 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxsphere) {
   BOOST_CHECK(dist <= 0);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(22.6, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(22.6, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(22.6, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(22.6, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.01);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(40, 0, 0)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(40, 0, 0)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 17.5) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(40, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(40, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 17.5) < 0.001);
 }
@@ -3832,7 +3832,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylindercylinder) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist;
@@ -3841,7 +3841,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylindercylinder) {
     // The following situations corresponds to the case where the two cylinders
     // are exactly superposed. This is the worst case for EPA which will take
     // forever to converge with default parameters.
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -3858,7 +3858,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylindercylinder) {
     solver1.epa_tolerance = 1e-2;
     solver1.epa_max_iterations = 1000;
 
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -3874,22 +3874,22 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylindercylinder) {
   }
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(10.1, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(10.1, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(40, 0, 0)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(40, 0, 0)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(40, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(40, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 0.001);
 }
@@ -3900,7 +3900,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecone) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist;
@@ -3909,7 +3909,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecone) {
     // The following situations corresponds to the case where the two cones
     // are exactly superposed. This is the worst case for EPA which will take
     // forever to converge with default parameters.
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -3926,7 +3926,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecone) {
     solver1.epa_tolerance = 1e-2;
     solver1.epa_max_iterations = 1000;
 
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -3942,22 +3942,22 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecone) {
   }
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(10.1, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(10.1, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.001);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(0, 0, 40)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(0, 0, 40)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 1);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(0, 0, 40)),
+      s1, transform, s2, transform * Transform3s(Vec3s(0, 0, 40)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 1);
 }
@@ -3968,7 +3968,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
   Vec3s closest_p1, closest_p2, normal;
   bool compute_penetration = true;
 
-  Transform3f transform;
+  Transform3s transform;
   generateRandomTransform(extents, transform);
 
   CoalScalar dist;
@@ -3977,7 +3977,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
     // The following situations corresponds to the case where the two cones
     // are exactly superposed. This is the worst case for EPA which will take
     // forever to converge with default parameters.
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -3994,7 +3994,7 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
     solver1.epa_tolerance = 1e-2;
     solver1.epa_max_iterations = 1000;
 
-    dist = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(),
+    dist = solver1.shapeDistance(s1, Transform3s(), s2, Transform3s(),
                                  compute_penetration, closest_p1, closest_p2,
                                  normal);
     BOOST_CHECK(dist <= 0);
@@ -4010,22 +4010,22 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
   }
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(10.1, 0, 0)),
+      s1, Transform3s(), s2, Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.01);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(10.1, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(10.1, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 0.1) < 0.02);
 
   dist = solver1.shapeDistance(
-      s1, Transform3f(), s2, Transform3f(Vec3s(40, 0, 0)), compute_penetration,
+      s1, Transform3s(), s2, Transform3s(Vec3s(40, 0, 0)), compute_penetration,
       closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 0.01);
 
   dist = solver1.shapeDistance(
-      s1, transform, s2, transform * Transform3f(Vec3s(40, 0, 0)),
+      s1, transform, s2, transform * Transform3s(Vec3s(40, 0, 0)),
       compute_penetration, closest_p1, closest_p2, normal);
   BOOST_CHECK(fabs(dist - 30) < 0.1);
 }
@@ -4033,8 +4033,8 @@ BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
 template <typename S1, typename S2>
 void testReversibleShapeDistance(const S1& s1, const S2& s2,
                                  CoalScalar distance) {
-  Transform3f tf1(Vec3s(-0.5 * distance, 0.0, 0.0));
-  Transform3f tf2(Vec3s(+0.5 * distance, 0.0, 0.0));
+  Transform3s tf1(Vec3s(-0.5 * distance, 0.0, 0.0));
+  Transform3s tf2(Vec3s(+0.5 * distance, 0.0, 0.0));
 
   CoalScalar distA;
   CoalScalar distB;
diff --git a/test/gjk.cpp b/test/gjk.cpp
index bb4d8996dfbcc41ef22cfde610ed182177f19961..9871029d5ef7921f87651dfb0c00aa97e662636e 100644
--- a/test/gjk.cpp
+++ b/test/gjk.cpp
@@ -51,7 +51,7 @@ using coal::GJKSolver;
 using coal::GJKVariant;
 using coal::Matrix3s;
 using coal::Quatf;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::TriangleP;
 using coal::Vec3s;
 
@@ -78,7 +78,7 @@ void test_gjk_distance_triangle_triangle(
   GJKSolver solver;
   if (enable_gjk_nesterov_acceleration)
     solver.gjk.gjk_variant = GJKVariant::NesterovAcceleration;
-  Transform3f tf1, tf2;
+  Transform3s tf1, tf2;
   Vec3s p1, p2, a1, a2;
   Matrix3s M;
   CoalScalar distance(sqrt(-1));
@@ -103,7 +103,7 @@ void test_gjk_distance_triangle_triangle(
           Vec3s(-25.655000000000001, -1.2858199462890625, 3.7249809570312502);
       Q2_loc = Vec3s(-10.926, -1.284259033203125, 3.7281499023437501);
       Q3_loc = Vec3s(-10.926, -1.2866180419921875, 3.72335400390625);
-      Transform3f tf(
+      Transform3s tf(
           Quatf(-0.42437287410898855, -0.26862477561450587,
                 -0.46249645019513175, 0.73064726592483387),
           Vec3s(-12.824601270753471, -1.6840516940066426, 3.8914453043793844));
@@ -131,7 +131,7 @@ void test_gjk_distance_triangle_triangle(
       tf1.setRotation(R);
       tf1.setTranslation(T);
     } else {
-      tf1 = Transform3f();
+      tf1 = Transform3s();
     }
 
     TriangleP tri1(P1_loc, P2_loc, P3_loc);
@@ -343,8 +343,8 @@ void test_gjk_unit_sphere(CoalScalar center_distance, Vec3s ray,
   sphere.setSweptSphereRadius(swept_sphere_radius);
 
   typedef Eigen::Matrix<CoalScalar, 4, 1> Vec4f;
-  Transform3f tf0(Quatf(Vec4f::Random().normalized()), Vec3s::Zero());
-  Transform3f tf1(Quatf(Vec4f::Random().normalized()), center_distance * ray);
+  Transform3s tf0(Quatf(Vec4f::Random().normalized()), Vec3s::Zero());
+  Transform3s tf1(Quatf(Vec4f::Random().normalized()), center_distance * ray);
 
   bool expect_collision = center_distance <= 2 * (r + swept_sphere_radius);
 
@@ -420,7 +420,7 @@ void test_gjk_triangle_capsule(Vec3s T, bool expect_collision,
   Capsule capsule(1., 2.);  // Radius 1 and length 2
   TriangleP triangle(Vec3s(0., 0., 0.), Vec3s(1., 0., 0.), Vec3s(1., 1., 0.));
 
-  Transform3f tf0, tf1;
+  Transform3s tf0, tf1;
   tf1.setTranslation(T);
 
   details::MinkowskiDiff shape;
diff --git a/test/gjk_asserts.cpp b/test/gjk_asserts.cpp
index d18a17f7cbe40885618943846571a9acfb854cdb..c4cb0be9873a3b7ef70eff571b38d4e7d70aa179 100644
--- a/test/gjk_asserts.cpp
+++ b/test/gjk_asserts.cpp
@@ -64,8 +64,8 @@ BOOST_AUTO_TEST_CASE(TestSpheres) {
 
   ComputeCollision compute(&sphere2, &sphere1);
 
-  Transform3f sphere1Tf = Transform3f::Identity();
-  Transform3f sphere2Tf = Transform3f::Identity();
+  Transform3s sphere1Tf = Transform3s::Identity();
+  Transform3s sphere2Tf = Transform3s::Identity();
 
   for (int i = 0; i < 360; ++i) {
     for (int j = 0; j < 180; ++j) {
diff --git a/test/gjk_convergence_criterion.cpp b/test/gjk_convergence_criterion.cpp
index 139df1ada1517d804500900d83d5e6a21fefdc59..6002c38be13093988c6696f9438e4087c2cea6f4 100644
--- a/test/gjk_convergence_criterion.cpp
+++ b/test/gjk_convergence_criterion.cpp
@@ -53,7 +53,7 @@ using coal::GJKConvergenceCriterionType;
 using coal::GJKSolver;
 using coal::ShapeBase;
 using coal::support_func_guess_t;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Vec3s;
 using coal::details::GJK;
 using coal::details::MinkowskiDiff;
@@ -123,9 +123,9 @@ void test_gjk_cv_criterion(const ShapeBase& shape0, const ShapeBase& shape1,
   // Generate random transforms
   size_t n = 1000;
   CoalScalar extents[] = {-3., -3., 0, 3., 3., 3.};
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
-  Transform3f identity = Transform3f::Identity();
+  Transform3s identity = Transform3s::Identity();
 
   // Same init for both solvers
   Vec3s init_guess = Vec3s(1, 0, 0);
diff --git a/test/hfields.cpp b/test/hfields.cpp
index a9fcc4c097be6a4db54128d0d6bf0f26ea0b0e4e..09d1b74492da3a4b27c8b4c415731cb47902a792 100644
--- a/test/hfields.cpp
+++ b/test/hfields.cpp
@@ -97,16 +97,16 @@ void test_constant_hfields(const Eigen::DenseIndex nx,
 
   // Build equivalent object
   const Box equivalent_box(x_dim, y_dim, max_altitude - min_altitude);
-  const Transform3f box_placement(
+  const Transform3s box_placement(
       Matrix3s::Identity(), Vec3s(0., 0., (max_altitude + min_altitude) / 2.));
 
   // Test collision
   const Sphere sphere(1.);
-  static const Transform3f IdTransform;
+  static const Transform3s IdTransform;
 
   const Box box(Vec3s::Ones());
 
-  Transform3f M_sphere, M_box;
+  Transform3s M_sphere, M_box;
 
   // No collision case
   {
@@ -281,16 +281,16 @@ void test_negative_security_margin(const Eigen::DenseIndex nx,
 
   // Build equivalent object
   const Box equivalent_box(x_dim, y_dim, max_altitude - min_altitude);
-  const Transform3f box_placement(
+  const Transform3s box_placement(
       Matrix3s::Identity(), Vec3s(0., 0., (max_altitude + min_altitude) / 2.));
 
   // Test collision
   const Sphere sphere(1.);
-  static const Transform3f IdTransform;
+  static const Transform3s IdTransform;
 
   const Box box(Vec3s::Ones());
 
-  Transform3f M_sphere, M_box;
+  Transform3s M_sphere, M_box;
 
   // No collision case
   {
@@ -430,8 +430,8 @@ BOOST_AUTO_TEST_CASE(hfield_with_square_hole) {
   const HeightField<BV> hfield(2., 2., heights, -10.);
 
   Sphere sphere(0.48);
-  const Transform3f sphere_pos(Vec3s(0., 0., 0.5));
-  const Transform3f hfield_pos;
+  const Transform3s sphere_pos(Vec3s(0., 0., 0.5));
+  const Transform3s hfield_pos;
 
   const CollisionRequest request;
 
@@ -480,8 +480,8 @@ BOOST_AUTO_TEST_CASE(hfield_with_circular_hole) {
   BOOST_CHECK(hfield.getYGrid()[ny - 1] == -1.);
 
   Sphere sphere(0.975);
-  const Transform3f sphere_pos(Vec3s(0., 0., 1.));
-  const Transform3f hfield_pos;
+  const Transform3s sphere_pos(Vec3s(0., 0., 1.));
+  const Transform3s hfield_pos;
 
   const CoalScalar thresholds[3] = {0., 0.01, -0.005};
 
@@ -728,8 +728,8 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the TOP
   {
-    const Transform3f sphere_pos(Vec3s(0., 0., 2.));
-    const Transform3f hfield_pos;
+    const Transform3s sphere_pos(Vec3s(0., 0., 2.));
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -743,8 +743,8 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Same, but with a positive margin.
   {
-    const Transform3f sphere_pos(Vec3s(0., 0., 2.));
-    const Transform3f hfield_pos;
+    const Transform3s sphere_pos(Vec3s(0., 0., 2.));
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -763,8 +763,8 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the BOTTOM
   {
-    const Transform3f sphere_pos(Vec3s(0., 0., -1.));
-    const Transform3f hfield_pos;
+    const Transform3s sphere_pos(Vec3s(0., 0., -1.));
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -775,8 +775,8 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
   }
 
   {
-    const Transform3f sphere_pos(Vec3s(0., 0., -1.));
-    const Transform3f hfield_pos;
+    const Transform3s sphere_pos(Vec3s(0., 0., -1.));
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -795,9 +795,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the WEST
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(hfield.getXGrid()[0] - sphere_radius, 0., 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -808,9 +808,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
   }
 
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(hfield.getXGrid()[0] - sphere_radius, 0., 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -827,9 +827,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the EAST
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(hfield.getXGrid()[1] + sphere_radius, 0., 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -840,9 +840,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
   }
 
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(hfield.getXGrid()[1] + sphere_radius, 0., 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -860,9 +860,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the NORTH
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(0., hfield.getYGrid()[0] + sphere_radius, 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -873,9 +873,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
   }
 
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(0., hfield.getYGrid()[0] + sphere_radius, 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -893,9 +893,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
 
   // Collision from the SOUTH
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(0., hfield.getYGrid()[1] - sphere_radius, 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
@@ -906,9 +906,9 @@ BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
   }
 
   {
-    const Transform3f sphere_pos(
+    const Transform3s sphere_pos(
         Vec3s(0., hfield.getYGrid()[1] - sphere_radius, 0.5));
-    const Transform3f hfield_pos;
+    const Transform3s hfield_pos;
 
     CollisionResult result;
     CollisionRequest request;
diff --git a/test/math.cpp b/test/math.cpp
index 2317390303661fe2573d56e72019ceed84f33934..c0f16ff3ee46ba53c249cd5f6cdceaaa3e203c5e 100644
--- a/test/math.cpp
+++ b/test/math.cpp
@@ -126,14 +126,14 @@ BOOST_AUTO_TEST_CASE(quaternion) {
 BOOST_AUTO_TEST_CASE(transform) {
   Quatf q = fromAxisAngle(Vec3s(0, 0, 1), M_PI / 2);
   Vec3s T(0, 1, 2);
-  Transform3f tf(q, T);
+  Transform3s tf(q, T);
 
   Vec3s v(1, -1, 0);
 
   BOOST_CHECK(isEqual(q * v + T, q * v + T));
 
   Vec3s rv(q * v);
-  // typename Transform3f::transform_return_type<Vec3s>::type output =
+  // typename Transform3s::transform_return_type<Vec3s>::type output =
   // tf * v;
   // std::cout << rv << std::endl;
   // std::cout << output.lhs() << std::endl;
@@ -142,7 +142,7 @@ BOOST_AUTO_TEST_CASE(transform) {
 
 BOOST_AUTO_TEST_CASE(random_transform) {
   for (size_t i = 0; i < 100; ++i) {
-    const Transform3f tf = Transform3f::Random();
+    const Transform3s tf = Transform3s::Random();
     BOOST_CHECK((tf.inverseTimes(tf)).isIdentity());
   }
 }
diff --git a/test/normal_and_nearest_points.cpp b/test/normal_and_nearest_points.cpp
index 76e62af0fbe8b5083cee59bb14436c803292c41b..3227774808410b9faebb60bf5d18f112553ea25a 100644
--- a/test/normal_and_nearest_points.cpp
+++ b/test/normal_and_nearest_points.cpp
@@ -87,9 +87,9 @@ void test_normal_and_nearest_points(
   // We want to make sure we generate poses that are in collision
   // so we take a relatively small extent for the random poses
   CoalScalar extents[] = {-1.5, -1.5, -1.5, 1.5, 1.5, 1.5};
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
-  Transform3f tf1 = Transform3f::Identity();
+  Transform3s tf1 = Transform3s::Identity();
 
   CollisionRequest colreq;
   colreq.distance_upper_bound = std::numeric_limits<CoalScalar>::max();
@@ -114,7 +114,7 @@ void test_normal_and_nearest_points(
     // Since CollisionRequest::distance_lower_bound is set to infinity,
     // these functions should agree on the results regardless of collision or
     // not.
-    Transform3f tf2 = transforms[i];
+    Transform3s tf2 = transforms[i];
     CollisionResult colres;
     DistanceResult distres;
     size_t col = collide(&o1, tf1, &o2, tf2, colreq, colres);
@@ -146,7 +146,7 @@ void test_normal_and_nearest_points(
       }
 
       // Separate the shapes
-      Transform3f new_tf1 = tf1;
+      Transform3s new_tf1 = tf1;
       CoalScalar eps = 1e-2;
       new_tf1.setTranslation(tf1.getTranslation() + separation_vector -
                              eps * contact.normal);
@@ -200,7 +200,7 @@ void test_normal_and_nearest_points(
       // happens to be parallel to the axis of the cone, the two shapes will
       // still be disjoint.
       CoalScalar eps = 1e-2;
-      Transform3f new_tf1 = tf1;
+      Transform3s new_tf1 = tf1;
       new_tf1.setTranslation(tf1.getTranslation() + separation_vector +
                              eps * distres.normal);
       CollisionResult new_colres;
@@ -625,10 +625,10 @@ void test_normal_and_nearest_points(const BVHModel<OBBRSS>& o1,
   size_t n = 10000;
 #endif
   CoalScalar extents[] = {-2., -2., -2., 2., 2., 2.};
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   generateRandomTransforms(extents, transforms, n);
-  Transform3f tf1 = Transform3f::Identity();
-  transforms[0] = Transform3f::Identity();
+  Transform3s tf1 = Transform3s::Identity();
+  transforms[0] = Transform3s::Identity();
 
   CollisionRequest colreq;
   colreq.distance_upper_bound = std::numeric_limits<CoalScalar>::max();
@@ -638,7 +638,7 @@ void test_normal_and_nearest_points(const BVHModel<OBBRSS>& o1,
   DistanceResult distres;
 
   for (size_t i = 0; i < n; i++) {
-    Transform3f tf2 = transforms[i];
+    Transform3s tf2 = transforms[i];
     colres.clear();
     distres.clear();
     size_t col = collide(&o1, tf1, &o2, tf2, colreq, colres);
@@ -683,7 +683,7 @@ BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_bvh_halfspace) {
   Box* box_ptr = new coal::Box(1, 1, 1);
   coal::CollisionGeometryPtr_t b1(box_ptr);
   BVHModel<coal::OBBRSS> o1 = BVHModel<OBBRSS>();
-  generateBVHModel(o1, *box_ptr, Transform3f());
+  generateBVHModel(o1, *box_ptr, Transform3s());
   o1.buildConvexRepresentation(false);
 
   CoalScalar offset = 0.1;
diff --git a/test/obb.cpp b/test/obb.cpp
index 77c16fe3ca4777d0aa6e3355d2254a5ff54bee3c..134a8daa2d5d6dc5aef08e134748d0bfac9691ae 100644
--- a/test/obb.cpp
+++ b/test/obb.cpp
@@ -107,7 +107,7 @@ bool distance(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,
               CoalScalar& distance) {
   GJKSolver gjk;
   Box ba(2 * a), bb(2 * b);
-  Transform3f tfa, tfb(B, T);
+  Transform3s tfa, tfb(B, T);
 
   Vec3s p1, p2, normal;
   bool compute_penetration = true;
diff --git a/test/octree.cpp b/test/octree.cpp
index 9cedd2e6c1dbe932e805798f22ecb5200dcf360a..d7f3b5d354ed03a07debe056f9672a773dead213 100644
--- a/test/octree.cpp
+++ b/test/octree.cpp
@@ -73,7 +73,7 @@ coal::OcTree makeOctree(const BVHModel<OBBRSS>& mesh,
   coal::Box box(resolution, resolution, resolution);
   CollisionRequest request(coal::CONTACT | coal::DISTANCE_LOWER_BOUND, 1);
   CollisionResult result;
-  Transform3f tfBox;
+  Transform3s tfBox;
   octomap::OcTreePtr_t octree(new octomap::OcTree(resolution));
 
   for (CoalScalar x = resolution * floor(m[0] / resolution); x <= M[0];
@@ -85,7 +85,7 @@ coal::OcTree makeOctree(const BVHModel<OBBRSS>& mesh,
         Vec3s center(x + .5 * resolution, y + .5 * resolution,
                      z + .5 * resolution);
         tfBox.setTranslation(center);
-        coal::collide(&box, tfBox, &mesh, Transform3f(), request, result);
+        coal::collide(&box, tfBox, &mesh, Transform3s(), request, result);
         if (result.isCollision()) {
           octomap::point3d p((float)center[0], (float)center[1],
                              (float)center[2]);
@@ -139,7 +139,7 @@ BOOST_AUTO_TEST_CASE(octree_mesh) {
                                                         3 * sizeof(CoalScalar));
   }
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-2000, -2000, 0, 2000, 2000, 2000};
 #ifndef NDEBUG  // if debug mode
   std::size_t N = 100;
@@ -155,8 +155,8 @@ BOOST_AUTO_TEST_CASE(octree_mesh) {
   for (std::size_t i = 0; i < N; ++i) {
     CollisionResult resultMesh;
     CollisionResult resultOctree;
-    Transform3f tf1(transforms[2 * i]);
-    Transform3f tf2(transforms[2 * i + 1]);
+    Transform3s tf1(transforms[2 * i]);
+    Transform3s tf2(transforms[2 * i + 1]);
     ;
     // Test collision between meshes with random transform for robot.
     coal::collide(&robMesh, tf1, &envMesh, tf2, request, resultMesh);
@@ -204,7 +204,7 @@ BOOST_AUTO_TEST_CASE(octree_height_field) {
   HeightField<AABB> hfield(x_dim, y_dim, heights, min_altitude);
   hfield.computeLocalAABB();
 
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
   CoalScalar extents[] = {-2000, -2000, 0, 2000, 2000, 2000};
 #ifndef NDEBUG  // if debug mode
   std::size_t N = 1000;
@@ -220,11 +220,11 @@ BOOST_AUTO_TEST_CASE(octree_height_field) {
   for (std::size_t i = 0; i < N; ++i) {
     CollisionResult resultBox;
     CollisionResult resultHfield1, resultHfield2;
-    Transform3f tf1(transforms[2 * i]);
-    Transform3f tf2(transforms[2 * i + 1]);
+    Transform3s tf1(transforms[2 * i]);
+    Transform3s tf2(transforms[2 * i + 1]);
 
     Box box;
-    Transform3f box_tf;
+    Transform3s box_tf;
     constructBox(hfield.aabb_local, tf2, box, box_tf);
 
     // Test collision between octree and equivalent box.
diff --git a/test/profiling.cpp b/test/profiling.cpp
index 5319e422ccf65810460abcb16488580926ceaddf..ab97a9648ba438f2dbd8c030d7061865aa3e8590 100644
--- a/test/profiling.cpp
+++ b/test/profiling.cpp
@@ -82,10 +82,10 @@ struct Results {
   Results(size_t i) : rs(i), times((Eigen::DenseIndex)i) {}
 };
 
-void collide(const std::vector<Transform3f>& tf, const CollisionGeometry* o1,
+void collide(const std::vector<Transform3s>& tf, const CollisionGeometry* o1,
              const CollisionGeometry* o2, const CollisionRequest& request,
              Results& results) {
-  Transform3f Id;
+  Transform3s Id;
   BenchTimer timer;
   for (std::size_t i = 0; i < tf.size(); ++i) {
     timer.start();
@@ -199,7 +199,7 @@ Geometry makeGeomFromParam(int& iarg, const int& argc, char** argv) {
       o->computeLocalAABB();
       OUT("Mesh AABB is " << o->aabb_local.min_.transpose() << " ---- "
                           << o->aabb_local.max_.transpose() << " ...");
-      o.reset(extract(o.get(), Transform3f(), aabb));
+      o.reset(extract(o.get(), Transform3s(), aabb));
       if (!o) throw std::invalid_argument("Failed to crop.");
       OUT("Crop has " << dynamic_pointer_cast<BVHModel<OBB> >(o)->num_tris
                       << " triangles");
@@ -221,7 +221,7 @@ Geometry makeGeomFromParam(int& iarg, const int& argc, char** argv) {
 }
 
 int main(int argc, char** argv) {
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
 
   CollisionRequest request;
 
diff --git a/test/python_unit/api.py b/test/python_unit/api.py
index ac7331d46267426ee2a18d72c996c0ac7d30310c..f15b08f60a7bc980fbade18d3ea4d0fa62182a04 100644
--- a/test/python_unit/api.py
+++ b/test/python_unit/api.py
@@ -8,8 +8,8 @@ import numpy as np
 class TestMainAPI(TestCase):
     def test_collision(self):
         capsule = coal.Capsule(1.0, 2.0)
-        M1 = coal.Transform3f()
-        M2 = coal.Transform3f(np.eye(3), np.array([3, 0, 0]))
+        M1 = coal.Transform3s()
+        M2 = coal.Transform3s(np.eye(3), np.array([3, 0, 0]))
 
         req = coal.CollisionRequest()
         res = coal.CollisionResult()
@@ -18,8 +18,8 @@ class TestMainAPI(TestCase):
 
     def test_distance(self):
         capsule = coal.Capsule(1.0, 2.0)
-        M1 = coal.Transform3f()
-        M2 = coal.Transform3f(np.eye(3), np.array([3, 0, 0]))
+        M1 = coal.Transform3s()
+        M2 = coal.Transform3s(np.eye(3), np.array([3, 0, 0]))
 
         req = coal.DistanceRequest()
         res = coal.DistanceResult()
diff --git a/test/python_unit/collision.py b/test/python_unit/collision.py
index fbf543bced5bf2e67e473e74c04e92f41127705b..afd69d503181d33e16e9ad41f998cbc827f3b95f 100644
--- a/test/python_unit/collision.py
+++ b/test/python_unit/collision.py
@@ -27,19 +27,19 @@ class TestMainAPI(TestCase):
         req = coal.CollisionRequest()
         res = coal.CollisionResult()
 
-        M1 = coal.Transform3f()
-        M2 = coal.Transform3f(np.eye(3), np.array([0, 0, -0.1]))
+        M1 = coal.Transform3s()
+        M2 = coal.Transform3s(np.eye(3), np.array([0, 0, -0.1]))
         res.clear()
         coal.collide(convex, M1, halfspace, M2, req, res)
         self.assertFalse(coal.collide(convex, M1, halfspace, M2, req, res))
 
-        M1 = coal.Transform3f()
-        M2 = coal.Transform3f(np.eye(3), np.array([0, 0, 0.1]))
+        M1 = coal.Transform3s()
+        M2 = coal.Transform3s(np.eye(3), np.array([0, 0, 0.1]))
         res.clear()
         self.assertTrue(coal.collide(convex, M1, halfspace, M2, req, res))
 
-        M1 = coal.Transform3f()
-        M2 = coal.Transform3f(np.eye(3), np.array([0, 0, 2]))
+        M1 = coal.Transform3s()
+        M2 = coal.Transform3s(np.eye(3), np.array([0, 0, 2]))
         res.clear()
         self.assertTrue(coal.collide(convex, M1, halfspace, M2, req, res))
 
diff --git a/test/python_unit/collision_manager.py b/test/python_unit/collision_manager.py
index 9dfe8474fdd70961648e2e04bc1b0f8911667978..241fda1c6b18ac0ccd6c4d8b77d8d1b0aeb81113 100644
--- a/test/python_unit/collision_manager.py
+++ b/test/python_unit/collision_manager.py
@@ -4,14 +4,14 @@ import numpy as np
 sphere = coal.Sphere(0.5)
 sphere_obj = coal.CollisionObject(sphere)
 
-M_sphere = coal.Transform3f.Identity()
+M_sphere = coal.Transform3s.Identity()
 M_sphere.setTranslation(np.array([-0.6, 0.0, 0.0]))
 sphere_obj.setTransform(M_sphere)
 
 box = coal.Box(np.array([0.5, 0.5, 0.5]))
 box_obj = coal.CollisionObject(box)
 
-M_box = coal.Transform3f.Identity()
+M_box = coal.Transform3s.Identity()
 M_box.setTranslation(np.array([-0.6, 0.0, 0.0]))
 box_obj.setTransform(M_box)
 
diff --git a/test/security_margin.cpp b/test/security_margin.cpp
index c56dba7c135b38faafddd7ddd469890719a4f85c..5993343daea60b3683e9ac2b0e8669a7f53f99e1 100644
--- a/test/security_margin.cpp
+++ b/test/security_margin.cpp
@@ -54,7 +54,7 @@ using coal::CollisionRequest;
 using coal::CollisionResult;
 using coal::DistanceRequest;
 using coal::DistanceResult;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Vec3s;
 
 #define MATH_SQUARED(x) (x * x)
@@ -63,15 +63,15 @@ BOOST_AUTO_TEST_CASE(aabb_aabb) {
   CollisionGeometryPtr_t b1(new coal::Box(1, 1, 1));
   CollisionGeometryPtr_t b2(new coal::Box(1, 1, 1));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 1, 1));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 1, 1));
   coal::Box s1(1, 1, 1);
   coal::Box s2(1, 1, 1);
   const double tol = 1e-8;
 
   AABB bv1, bv2;
-  computeBV(s1, Transform3f(), bv1);
-  computeBV(s2, Transform3f(), bv2);
+  computeBV(s1, Transform3s(), bv1);
+  computeBV(s2, Transform3s(), bv2);
 
   // No security margin - collision
   {
@@ -89,7 +89,7 @@ BOOST_AUTO_TEST_CASE(aabb_aabb) {
   {
     CollisionRequest collisionRequest(CONTACT, 1);
     const double distance = 0.01;
-    Transform3f tf2_no_collision(
+    Transform3s tf2_no_collision(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, 0, distance)));
     AABB bv2_transformed;
     computeBV(s2, tf2_no_collision, bv2_transformed);
@@ -105,7 +105,7 @@ BOOST_AUTO_TEST_CASE(aabb_aabb) {
     CollisionRequest collisionRequest(CONTACT, 1);
     const double distance = 0.01;
     collisionRequest.security_margin = distance;
-    Transform3f tf2_no_collision(
+    Transform3s tf2_no_collision(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, 0, distance)));
     AABB bv2_transformed;
     computeBV(s2, tf2_no_collision, bv2_transformed);
@@ -121,7 +121,7 @@ BOOST_AUTO_TEST_CASE(aabb_aabb) {
     CollisionRequest collisionRequest(CONTACT, 1);
     const double distance = -0.01;
     collisionRequest.security_margin = distance;
-    const Transform3f tf2(
+    const Transform3s tf2(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, distance, distance)));
     AABB bv2_transformed;
     computeBV(s2, tf2, bv2_transformed);
@@ -153,14 +153,14 @@ BOOST_AUTO_TEST_CASE(aabb_aabb_degenerated_cases) {
   CollisionGeometryPtr_t b1(new coal::Box(1, 1, 1));
   CollisionGeometryPtr_t b2(new coal::Box(1, 1, 1));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 0, 0));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 0, 0));
   coal::Box s1(1, 1, 1);
   coal::Box s2(1, 1, 1);
 
   AABB bv1, bv2;
-  computeBV(s1, Transform3f(), bv1);
-  computeBV(s2, Transform3f(), bv2);
+  computeBV(s1, Transform3s(), bv1);
+  computeBV(s2, Transform3s(), bv2);
 
   // The two AABB are collocated
   {
@@ -183,8 +183,8 @@ BOOST_AUTO_TEST_CASE(sphere_sphere) {
   CollisionGeometryPtr_t s1(new coal::Sphere(1));
   CollisionGeometryPtr_t s2(new coal::Sphere(2));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 0, 3));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 0, 3));
 
   // NOTE: when comparing a result to zero, **do not use BOOST_CHECK_CLOSE**!
   // Zero is not close to any other number, so the test will always fail.
@@ -206,7 +206,7 @@ BOOST_AUTO_TEST_CASE(sphere_sphere) {
     CollisionRequest collisionRequest(CONTACT, 1);
     CollisionResult collisionResult;
     const double distance = 0.01;
-    Transform3f tf2_no_collision(
+    Transform3s tf2_no_collision(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, 0, distance)));
     collide(s1.get(), tf1, s2.get(), tf2_no_collision, collisionRequest,
             collisionResult);
@@ -220,7 +220,7 @@ BOOST_AUTO_TEST_CASE(sphere_sphere) {
     CollisionResult collisionResult;
     const double distance = 0.01;
     collisionRequest.security_margin = distance;
-    Transform3f tf2(
+    Transform3s tf2(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, 0, distance)));
     collide(s1.get(), tf1, s2.get(), tf2, collisionRequest, collisionResult);
     BOOST_CHECK(collisionResult.isCollision());
@@ -235,7 +235,7 @@ BOOST_AUTO_TEST_CASE(sphere_sphere) {
     CollisionResult collisionResult;
     const double distance = -0.01;
     collisionRequest.security_margin = distance;
-    Transform3f tf2(
+    Transform3s tf2(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, 0, distance)));
     collide(s1.get(), tf1, s2.get(), tf2, collisionRequest, collisionResult);
     BOOST_CHECK(collisionResult.isCollision());
@@ -261,8 +261,8 @@ BOOST_AUTO_TEST_CASE(capsule_capsule) {
   CollisionGeometryPtr_t c1(new coal::Capsule(0.5, 1.));
   CollisionGeometryPtr_t c2(new coal::Capsule(0.5, 1.));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 1., 0));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 1., 0));
 
   // No security margin - collision
   {
@@ -280,7 +280,7 @@ BOOST_AUTO_TEST_CASE(capsule_capsule) {
     CollisionRequest collisionRequest(CONTACT, 1);
     CollisionResult collisionResult;
     const double distance = 0.01;
-    Transform3f tf2_no_collision(
+    Transform3s tf2_no_collision(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, distance, 0)));
     collide(c1.get(), tf1, c2.get(), tf2_no_collision, collisionRequest,
             collisionResult);
@@ -294,7 +294,7 @@ BOOST_AUTO_TEST_CASE(capsule_capsule) {
     CollisionResult collisionResult;
     const double distance = 0.01;
     collisionRequest.security_margin = distance;
-    Transform3f tf2_no_collision(
+    Transform3s tf2_no_collision(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, distance, 0)));
     collide(c1.get(), tf1, c2.get(), tf2_no_collision, collisionRequest,
             collisionResult);
@@ -310,7 +310,7 @@ BOOST_AUTO_TEST_CASE(capsule_capsule) {
     CollisionResult collisionResult;
     const double distance = -0.01;
     collisionRequest.security_margin = distance;
-    Transform3f tf2(
+    Transform3s tf2(
         Vec3s(tf2_collision.getTranslation() + Vec3s(0, distance, 0)));
     collide(c1.get(), tf1, c2.get(), tf2, collisionRequest, collisionResult);
     BOOST_CHECK(collisionResult.isCollision());
@@ -335,8 +335,8 @@ BOOST_AUTO_TEST_CASE(box_box) {
   CollisionGeometryPtr_t b1(new coal::Box(1, 1, 1));
   CollisionGeometryPtr_t b2(new coal::Box(1, 1, 1));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 1, 1));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 1, 1));
 
   const double tol = 1e-3;
 
@@ -355,7 +355,7 @@ BOOST_AUTO_TEST_CASE(box_box) {
   {
     CollisionRequest collisionRequest(CONTACT, 1);
     const double distance = 0.01;
-    const Transform3f tf2_no_collision(
+    const Transform3s tf2_no_collision(
         (tf2_collision.getTranslation() + Vec3s(0, 0, distance)).eval());
 
     CollisionResult collisionResult;
@@ -398,7 +398,7 @@ BOOST_AUTO_TEST_CASE(box_box) {
     collisionRequest.security_margin = distance;
     CollisionResult collisionResult;
 
-    const Transform3f tf2((tf2_collision.getTranslation() +
+    const Transform3s tf2((tf2_collision.getTranslation() +
                            Vec3s(0, collisionRequest.security_margin,
                                  collisionRequest.security_margin))
                               .eval());
@@ -411,9 +411,9 @@ BOOST_AUTO_TEST_CASE(box_box) {
 }
 
 template <typename ShapeType1, typename ShapeType2>
-void test_shape_shape(const ShapeType1& shape1, const Transform3f& tf1,
+void test_shape_shape(const ShapeType1& shape1, const Transform3s& tf1,
                       const ShapeType2& shape2,
-                      const Transform3f& tf2_collision, const CoalScalar tol) {
+                      const Transform3s& tf2_collision, const CoalScalar tol) {
   // No security margin - collision
   {
     CollisionRequest collisionRequest(CONTACT, 1);
@@ -429,7 +429,7 @@ void test_shape_shape(const ShapeType1& shape1, const Transform3f& tf1,
   {
     CollisionRequest collisionRequest(CONTACT, 1);
     const double distance = 0.01;
-    const Transform3f tf2_no_collision(
+    const Transform3s tf2_no_collision(
         (tf2_collision.getTranslation() + Vec3s(0, 0, distance)).eval());
 
     CollisionResult collisionResult;
@@ -475,7 +475,7 @@ void test_shape_shape(const ShapeType1& shape1, const Transform3f& tf1,
     collisionRequest.security_margin = distance;
     CollisionResult collisionResult;
 
-    const Transform3f tf2((tf2_collision.getTranslation() +
+    const Transform3s tf2((tf2_collision.getTranslation() +
                            Vec3s(0, collisionRequest.security_margin,
                                  collisionRequest.security_margin))
                               .eval());
@@ -491,13 +491,13 @@ BOOST_AUTO_TEST_CASE(sphere_box) {
   Box* box_ptr = new coal::Box(1, 1, 1);
   CollisionGeometryPtr_t b1(box_ptr);
   BVHModel<OBBRSS> box_bvh_model = BVHModel<OBBRSS>();
-  generateBVHModel(box_bvh_model, *box_ptr, Transform3f());
+  generateBVHModel(box_bvh_model, *box_ptr, Transform3s());
   box_bvh_model.buildConvexRepresentation(false);
   ConvexBase& box_convex = *box_bvh_model.convex.get();
   CollisionGeometryPtr_t s2(new coal::Sphere(0.5));
 
-  const Transform3f tf1;
-  const Transform3f tf2_collision(Vec3s(0, 0, 1));
+  const Transform3s tf1;
+  const Transform3s tf2_collision(Vec3s(0, 0, 1));
 
   const double tol = 1e-6;
 
diff --git a/test/serialization.cpp b/test/serialization.cpp
index c1dc66fbdfaf0d4c3d2fe8c80d748340c8102b0e..f54ace2d1f6a3ee7493662f95799c4572ce709e1 100644
--- a/test/serialization.cpp
+++ b/test/serialization.cpp
@@ -286,8 +286,8 @@ BOOST_AUTO_TEST_CASE(test_collision_data) {
     const CoalScalar height = 1.;
     const Cylinder cylinder(radius, height);
 
-    const Transform3f tf1;
-    Transform3f tf2;
+    const Transform3s tf1;
+    Transform3s tf2;
     // set translation to have a collision
     const CoalScalar offset = 0.001;
     tf2.setTranslation(Vec3s(0, 0, height / 2 - offset));
@@ -436,11 +436,11 @@ BOOST_AUTO_TEST_CASE(test_HeightField) {
 }
 
 BOOST_AUTO_TEST_CASE(test_transform) {
-  Transform3f T;
+  Transform3s T;
   T.setQuatRotation(Quaternion3f::UnitRandom());
   T.setTranslation(Vec3s::Random());
 
-  Transform3f T_copy;
+  Transform3s T_copy;
   test_serialization(T, T_copy);
 }
 
diff --git a/test/shape_inflation.cpp b/test/shape_inflation.cpp
index a571c380a549b4fd545c5f9c68ddb94ab266327c..cfd321024aeb80e61a8abebd582490c3d3d3a9a8 100644
--- a/test/shape_inflation.cpp
+++ b/test/shape_inflation.cpp
@@ -53,7 +53,7 @@ using coal::CollisionRequest;
 using coal::CollisionResult;
 using coal::DistanceRequest;
 using coal::DistanceResult;
-using coal::Transform3f;
+using coal::Transform3s;
 using coal::Vec3s;
 
 #define MATH_SQUARED(x) (x * x)
@@ -114,7 +114,7 @@ void test(const Shape &original_shape, const CoalScalar inflation,
   {
     const CoalScalar inflation = 0.;
     const auto &inflation_result = original_shape.inflated(inflation);
-    const Transform3f &shift = inflation_result.second;
+    const Transform3s &shift = inflation_result.second;
     const Shape &inflated_shape = inflation_result.first;
 
     BOOST_CHECK(isApprox(original_shape, inflated_shape, tol));
@@ -125,13 +125,13 @@ void test(const Shape &original_shape, const CoalScalar inflation,
   {
     const auto &inflation_result = original_shape.inflated(inflation);
     const Shape &inflated_shape = inflation_result.first;
-    const Transform3f &inflation_shift = inflation_result.second;
+    const Transform3s &inflation_shift = inflation_result.second;
 
     BOOST_CHECK(!isApprox(original_shape, inflated_shape, tol));
 
     const auto &deflation_result = inflated_shape.inflated(-inflation);
     const Shape &deflated_shape = deflation_result.first;
-    const Transform3f &deflation_shift = deflation_result.second;
+    const Transform3s &deflation_shift = deflation_result.second;
 
     BOOST_CHECK(isApprox(original_shape, deflated_shape, tol));
     BOOST_CHECK((inflation_shift * deflation_shift).isIdentity(tol));
@@ -141,13 +141,13 @@ void test(const Shape &original_shape, const CoalScalar inflation,
   {
     const auto &inflation_result = original_shape.inflated(-inflation);
     const Shape &inflated_shape = inflation_result.first;
-    const Transform3f &inflation_shift = inflation_result.second;
+    const Transform3s &inflation_shift = inflation_result.second;
 
     BOOST_CHECK(!isApprox(original_shape, inflated_shape, tol));
 
     const auto &deflation_result = inflated_shape.inflated(+inflation);
     const Shape &deflated_shape = deflation_result.first;
-    const Transform3f &deflation_shift = deflation_result.second;
+    const Transform3s &deflation_shift = deflation_result.second;
 
     BOOST_CHECK(isApprox(original_shape, deflated_shape, tol));
     BOOST_CHECK((inflation_shift * deflation_shift).isIdentity(tol));
diff --git a/test/shape_mesh_consistency.cpp b/test/shape_mesh_consistency.cpp
index d234602efec8c467412bdeb45dd7a3f989456afd..6b8d35e33b9d6f548b6382e03485421cb1110295 100644
--- a/test/shape_mesh_consistency.cpp
+++ b/test/shape_mesh_consistency.cpp
@@ -56,39 +56,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(50, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -111,27 +111,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere) {
   pose.setTranslation(Vec3s(40.1, 0, 0));
 
   res.clear(), res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -159,39 +159,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_boxbox) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f());
-  generateBVHModel(s2_rss, s2, Transform3f());
+  generateBVHModel(s1_rss, s1, Transform3s());
+  generateBVHModel(s2_rss, s2, Transform3s());
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(50, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -215,27 +215,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_boxbox) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -263,39 +263,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(20, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -320,27 +320,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -368,38 +368,38 @@ BOOST_AUTO_TEST_CASE(consistency_distance_conecone) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(20, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -424,27 +424,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_conecone) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -471,39 +471,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_GJK) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(50, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -527,27 +527,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_GJK) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               4);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -575,39 +575,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_boxbox_GJK) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f());
-  generateBVHModel(s2_rss, s2, Transform3f());
+  generateBVHModel(s1_rss, s1, Transform3s());
+  generateBVHModel(s2_rss, s2, Transform3s());
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(50, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.01);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -631,27 +631,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_boxbox_GJK) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -679,39 +679,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder_GJK) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(20, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -747,27 +747,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder_GJK) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -795,39 +795,39 @@ BOOST_AUTO_TEST_CASE(consistency_distance_conecone_GJK) {
   BVHModel<RSS> s1_rss;
   BVHModel<RSS> s2_rss;
 
-  generateBVHModel(s1_rss, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_rss, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_rss, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_rss, s2, Transform3s(), 16, 16);
 
   DistanceRequest request;
   DistanceResult res, res1;
 
-  Transform3f pose;
+  Transform3s pose;
 
   pose.setTranslation(Vec3s(20, 0, 0));
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               0.05);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -851,27 +851,27 @@ BOOST_AUTO_TEST_CASE(consistency_distance_conecone_GJK) {
 
   res.clear();
   res1.clear();
-  distance(&s1, Transform3f(), &s2, pose, request, res);
-  distance(&s1_rss, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2, pose, request, res);
+  distance(&s1_rss, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1, Transform3f(), &s2_rss, pose, request, res1);
+  distance(&s1, Transform3s(), &s2_rss, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   res1.clear();
-  distance(&s1_rss, Transform3f(), &s2, pose, request, res1);
+  distance(&s1_rss, Transform3s(), &s2, pose, request, res1);
   BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance <
               2);
 
   for (std::size_t i = 0; i < 10; ++i) {
-    Transform3f t;
+    Transform3s t;
     generateRandomTransform(extents, t);
 
-    Transform3f pose1(t);
-    Transform3f pose2 = t * pose;
+    Transform3s pose1(t);
+    Transform3s pose2 = t * pose;
 
     res.clear();
     res1.clear();
@@ -900,17 +900,17 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
   CollisionResult result;
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -918,31 +918,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(40, 0, 0));
@@ -950,31 +950,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
   pose_obb.setTranslation(Vec3s(40, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(30, 0, 0));
@@ -982,31 +982,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
   pose_obb.setTranslation(Vec3s(30, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(29.9, 0, 0));
@@ -1016,31 +1016,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
       Vec3s(29.8, 0, 0));  // 29.9 fails, result depends on mesh precision
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(-29.9, 0, 0));
@@ -1050,31 +1050,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
       Vec3s(-29.8, 0, 0));  // 29.9 fails, result depends on mesh precision
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(-30, 0, 0));
@@ -1082,31 +1082,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
   pose_obb.setTranslation(Vec3s(-30, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -1119,17 +1119,17 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f());
-  generateBVHModel(s2_aabb, s2, Transform3f());
-  generateBVHModel(s1_obb, s1, Transform3f());
-  generateBVHModel(s2_obb, s2, Transform3f());
+  generateBVHModel(s1_aabb, s1, Transform3s());
+  generateBVHModel(s2_aabb, s2, Transform3s());
+  generateBVHModel(s1_obb, s1, Transform3s());
+  generateBVHModel(s2_obb, s2, Transform3s());
 
   CollisionRequest request(false, 1, false);
   CollisionResult result;
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -1137,31 +1137,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(15.01, 0, 0));
@@ -1169,31 +1169,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox) {
   pose_obb.setTranslation(Vec3s(15.01, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(14.99, 0, 0));
@@ -1201,31 +1201,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox) {
   pose_obb.setTranslation(Vec3s(14.99, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 }
 
@@ -1238,17 +1238,17 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f());
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f());
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s());
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s());
 
   CollisionRequest request(false, 1, false);
   CollisionResult result;
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -1256,31 +1256,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(22.4, 0, 0));
@@ -1288,31 +1288,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox) {
   pose_obb.setTranslation(Vec3s(22.4, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(22.51, 0, 0));
@@ -1320,31 +1320,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox) {
   pose_obb.setTranslation(Vec3s(22.51, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -1357,48 +1357,48 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
   CollisionResult result;
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   pose.setTranslation(Vec3s(9.99, 0, 0));
   pose_aabb.setTranslation(Vec3s(9.99, 0, 0));
   pose_obb.setTranslation(Vec3s(9.99, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(10.01, 0, 0));
@@ -1406,31 +1406,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder) {
   pose_obb.setTranslation(Vec3s(10.01, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -1443,48 +1443,48 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
   CollisionResult result;
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   pose.setTranslation(Vec3s(9.9, 0, 0));
   pose_aabb.setTranslation(Vec3s(9.9, 0, 0));
   pose_obb.setTranslation(Vec3s(9.9, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(10.1, 0, 0));
@@ -1492,31 +1492,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone) {
   pose_obb.setTranslation(Vec3s(10.1, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(0, 0, 9.9));
@@ -1524,31 +1524,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone) {
   pose_obb.setTranslation(Vec3s(0, 0, 9.9));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(0, 0, 10.1));
@@ -1556,31 +1556,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone) {
   pose_obb.setTranslation(Vec3s(0, 0, 10.1));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -1592,10 +1592,10 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
 
@@ -1603,7 +1603,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -1611,31 +1611,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(40, 0, 0));
@@ -1643,31 +1643,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
   pose_obb.setTranslation(Vec3s(40, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(30, 0, 0));
@@ -1675,31 +1675,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
   pose_obb.setTranslation(Vec3s(30, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(29.9, 0, 0));
@@ -1709,31 +1709,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
       Vec3s(29.8, 0, 0));  // 29.9 fails, result depends on mesh precision
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(-29.9, 0, 0));
@@ -1743,31 +1743,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
       Vec3s(-29.8, 0, 0));  // 29.9 fails, result depends on mesh precision
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(-30, 0, 0));
@@ -1775,31 +1775,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
   pose_obb.setTranslation(Vec3s(-30, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -1812,10 +1812,10 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f());
-  generateBVHModel(s2_aabb, s2, Transform3f());
-  generateBVHModel(s1_obb, s1, Transform3f());
-  generateBVHModel(s2_obb, s2, Transform3f());
+  generateBVHModel(s1_aabb, s1, Transform3s());
+  generateBVHModel(s2_aabb, s2, Transform3s());
+  generateBVHModel(s1_obb, s1, Transform3s());
+  generateBVHModel(s2_obb, s2, Transform3s());
 
   CollisionRequest request(false, 1, false);
 
@@ -1823,7 +1823,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -1831,31 +1831,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(15.01, 0, 0));
@@ -1863,31 +1863,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
   pose_obb.setTranslation(Vec3s(15.01, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(14.99, 0, 0));
@@ -1895,31 +1895,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
   pose_obb.setTranslation(Vec3s(14.99, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 }
 
@@ -1932,10 +1932,10 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f());
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f());
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s());
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s());
 
   CollisionRequest request(false, 1, false);
 
@@ -1943,7 +1943,7 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   // s2 is within s1
   // both are shapes --> collision
@@ -1951,31 +1951,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
   // s1 is mesh, s2 is shape --> collision free
   // all are reasonable
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(22.4, 0, 0));
@@ -1983,31 +1983,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
   pose_obb.setTranslation(Vec3s(22.4, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(22.51, 0, 0));
@@ -2015,31 +2015,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
   pose_obb.setTranslation(Vec3s(22.51, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -2052,10 +2052,10 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
 
@@ -2063,38 +2063,38 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK) {
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   pose.setTranslation(Vec3s(9.99, 0, 0));
   pose_aabb.setTranslation(Vec3s(9.99, 0, 0));
   pose_obb.setTranslation(Vec3s(9.99, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(10.01, 0, 0));
@@ -2102,31 +2102,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK) {
   pose_obb.setTranslation(Vec3s(10.01, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
 
@@ -2139,10 +2139,10 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
   BVHModel<OBB> s1_obb;
   BVHModel<OBB> s2_obb;
 
-  generateBVHModel(s1_aabb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_aabb, s2, Transform3f(), 16, 16);
-  generateBVHModel(s1_obb, s1, Transform3f(), 16, 16);
-  generateBVHModel(s2_obb, s2, Transform3f(), 16, 16);
+  generateBVHModel(s1_aabb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_aabb, s2, Transform3s(), 16, 16);
+  generateBVHModel(s1_obb, s1, Transform3s(), 16, 16);
+  generateBVHModel(s2_obb, s2, Transform3s(), 16, 16);
 
   CollisionRequest request(false, 1, false);
 
@@ -2150,38 +2150,38 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
 
   bool res;
 
-  Transform3f pose, pose_aabb, pose_obb;
+  Transform3s pose, pose_aabb, pose_obb;
 
   pose.setTranslation(Vec3s(9.9, 0, 0));
   pose_aabb.setTranslation(Vec3s(9.9, 0, 0));
   pose_obb.setTranslation(Vec3s(9.9, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(10.1, 0, 0));
@@ -2189,31 +2189,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
   pose_obb.setTranslation(Vec3s(10.1, 0, 0));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 
   pose.setTranslation(Vec3s(0, 0, 9.9));
@@ -2221,31 +2221,31 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
   pose_obb.setTranslation(Vec3s(0, 0, 9.9));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK(res);
 
   pose.setTranslation(Vec3s(0, 0, 10.1));
@@ -2253,30 +2253,30 @@ BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
   pose_obb.setTranslation(Vec3s(0, 0, 10.1));
 
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_aabb, pose_aabb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), request, result) > 0);
+  res = (collide(&s2_obb, pose_obb, &s1, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_aabb, pose_aabb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, request, result) > 0);
+  res = (collide(&s1, Transform3s(), &s2_obb, pose_obb, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_aabb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_aabb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s2, pose, &s1_obb, Transform3f(), request, result) > 0);
+  res = (collide(&s2, pose, &s1_obb, Transform3s(), request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
   result.clear();
-  res = (collide(&s1_aabb, Transform3f(), &s2, pose, request, result) > 0);
+  res = (collide(&s1_aabb, Transform3s(), &s2, pose, request, result) > 0);
   BOOST_CHECK_FALSE(res);
 }
diff --git a/test/swept_sphere_radius.cpp b/test/swept_sphere_radius.cpp
index b1a687a91a16e70cd1e0d8d67bea97d3bcf2c2ae..e43d92ec29cae99e93ef0da3f90cc7204b98e6ba 100644
--- a/test/swept_sphere_radius.cpp
+++ b/test/swept_sphere_radius.cpp
@@ -114,8 +114,8 @@ int line;
 struct SweptSphereGJKSolver : public GJKSolver {
   template <typename S1, typename S2>
   CoalScalar shapeDistance(
-      const S1& s1, const Transform3f& tf1, const S2& s2,
-      const Transform3f& tf2, bool compute_penetration, Vec3s& p1, Vec3s& p2,
+      const S1& s1, const Transform3s& tf1, const S2& s2,
+      const Transform3s& tf2, bool compute_penetration, Vec3s& p1, Vec3s& p2,
       Vec3s& normal, bool use_swept_sphere_radius_in_gjk_epa_iterations) const {
     if (use_swept_sphere_radius_in_gjk_epa_iterations) {
       CoalScalar distance;
@@ -146,8 +146,8 @@ void test_gjksolver_swept_sphere_radius(S1& shape1, S2& shape2) {
 
   CoalScalar extents[] = {-2, -2, -2, 2, 2, 2};
   std::size_t n = 10;
-  std::vector<Transform3f> tf1s;
-  std::vector<Transform3f> tf2s;
+  std::vector<Transform3s> tf1s;
+  std::vector<Transform3s> tf2s;
   generateRandomTransforms(extents, tf1s, n);
   generateRandomTransforms(extents, tf2s, n);
   const std::array<CoalScalar, 4> swept_sphere_radius = {0, 0.1, 1., 10.};
@@ -157,8 +157,8 @@ void test_gjksolver_swept_sphere_radius(S1& shape1, S2& shape2) {
     for (const CoalScalar& ssr2 : swept_sphere_radius) {
       shape2.setSweptSphereRadius(ssr2);
       for (std::size_t i = 0; i < n; ++i) {
-        Transform3f tf1 = tf1s[i];
-        Transform3f tf2 = tf2s[i];
+        Transform3s tf1 = tf1s[i];
+        Transform3s tf2 = tf2s[i];
 
         SET_LINE;
 
@@ -283,8 +283,8 @@ void test_collide_swept_sphere_radius(S1& shape1, S2& shape2) {
 
   CoalScalar extents[] = {-2, -2, -2, 2, 2, 2};
   std::size_t n = 1;
-  std::vector<Transform3f> tf1s;
-  std::vector<Transform3f> tf2s;
+  std::vector<Transform3s> tf1s;
+  std::vector<Transform3s> tf2s;
   generateRandomTransforms(extents, tf1s, n);
   generateRandomTransforms(extents, tf2s, n);
 
@@ -294,8 +294,8 @@ void test_collide_swept_sphere_radius(S1& shape1, S2& shape2) {
     for (const CoalScalar& ssr2 : swept_sphere_radius) {
       shape2.setSweptSphereRadius(ssr2);
       for (std::size_t i = 0; i < n; ++i) {
-        Transform3f tf1 = tf1s[i];
-        Transform3f tf2 = tf2s[i];
+        Transform3s tf1 = tf1s[i];
+        Transform3s tf2 = tf2s[i];
 
         SET_LINE;
         CollisionRequest request;
diff --git a/test/utility.cpp b/test/utility.cpp
index 80efceba4166de32232abf519939e4e128cb2009..714469f019e57d14cd638f7af944287e49afa9af 100644
--- a/test/utility.cpp
+++ b/test/utility.cpp
@@ -207,7 +207,7 @@ void eulerToMatrix(CoalScalar a, CoalScalar b, CoalScalar c, Matrix3s& R) {
       -c2 * s3, s1 * s3 - c1 * c3 * s2, c3 * s1 * s2 + c1 * s3, c2 * c3;
 }
 
-void generateRandomTransform(CoalScalar extents[6], Transform3f& transform) {
+void generateRandomTransform(CoalScalar extents[6], Transform3s& transform) {
   CoalScalar x = rand_interval(extents[0], extents[3]);
   CoalScalar y = rand_interval(extents[1], extents[4]);
   CoalScalar z = rand_interval(extents[2], extents[5]);
@@ -224,7 +224,7 @@ void generateRandomTransform(CoalScalar extents[6], Transform3f& transform) {
 }
 
 void generateRandomTransforms(CoalScalar extents[6],
-                              std::vector<Transform3f>& transforms,
+                              std::vector<Transform3s>& transforms,
                               std::size_t n) {
   transforms.resize(n);
   for (std::size_t i = 0; i < n; ++i) {
@@ -248,8 +248,8 @@ void generateRandomTransforms(CoalScalar extents[6],
 
 void generateRandomTransforms(CoalScalar extents[6], CoalScalar delta_trans[3],
                               CoalScalar delta_rot,
-                              std::vector<Transform3f>& transforms,
-                              std::vector<Transform3f>& transforms2,
+                              std::vector<Transform3s>& transforms,
+                              std::vector<Transform3s>& transforms2,
                               std::size_t n) {
   transforms.resize(n);
   transforms2.resize(n);
@@ -376,7 +376,7 @@ Quatf makeQuat(CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z) {
   return q;
 }
 
-std::ostream& operator<<(std::ostream& os, const Transform3f& tf) {
+std::ostream& operator<<(std::ostream& os, const Transform3s& tf) {
   return os << "[ " << tf.getTranslation().format(vfmt) << ", "
             << tf.getQuatRotation().coeffs().format(vfmt) << " ]";
 }
@@ -393,7 +393,7 @@ void generateEnvironments(std::vector<CollisionObject*>& env,
                           CoalScalar env_scale, std::size_t n) {
   CoalScalar extents[] = {-env_scale, env_scale,  -env_scale,
                           env_scale,  -env_scale, env_scale};
-  std::vector<Transform3f> transforms(n);
+  std::vector<Transform3s> transforms(n);
 
   generateRandomTransforms(extents, transforms, n);
   for (std::size_t i = 0; i < n; ++i) {
@@ -424,13 +424,13 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env,
                               CoalScalar env_scale, std::size_t n) {
   CoalScalar extents[] = {-env_scale, env_scale,  -env_scale,
                           env_scale,  -env_scale, env_scale};
-  std::vector<Transform3f> transforms;
+  std::vector<Transform3s> transforms;
 
   generateRandomTransforms(extents, transforms, n);
   Box box(5, 10, 20);
   for (std::size_t i = 0; i < n; ++i) {
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, box, Transform3f::Identity());
+    generateBVHModel(*model, box, Transform3s::Identity());
     env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
                                       transforms[i]));
     env.back()->collisionGeometry()->computeLocalAABB();
@@ -440,7 +440,7 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env,
   Sphere sphere(30);
   for (std::size_t i = 0; i < n; ++i) {
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, sphere, Transform3f::Identity(), 16, 16);
+    generateBVHModel(*model, sphere, Transform3s::Identity(), 16, 16);
     env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
                                       transforms[i]));
     env.back()->collisionGeometry()->computeLocalAABB();
@@ -450,7 +450,7 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env,
   Cylinder cylinder(10, 40);
   for (std::size_t i = 0; i < n; ++i) {
     BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
-    generateBVHModel(*model, cylinder, Transform3f::Identity(), 16, 16);
+    generateBVHModel(*model, cylinder, Transform3s::Identity(), 16, 16);
     env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
                                       transforms[i]));
     env.back()->collisionGeometry()->computeLocalAABB();
diff --git a/test/utility.h b/test/utility.h
index 2969bb288c14d33e6e83fa0755f5d2f4ca866d15..6be386e5e012dfc18b8f26c0faac7f813452da7e 100644
--- a/test/utility.h
+++ b/test/utility.h
@@ -146,12 +146,12 @@ coal::OcTree loadOctreeFile(const std::string& filename,
 /// extents and rotation without constraints. The translation is (x, y, z), and
 /// extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <=
 /// z <= extents[5]
-void generateRandomTransform(CoalScalar extents[6], Transform3f& transform);
+void generateRandomTransform(CoalScalar extents[6], Transform3s& transform);
 
 /// @brief Generate n random transforms whose translations are constrained by
 /// extents.
 void generateRandomTransforms(CoalScalar extents[6],
-                              std::vector<Transform3f>& transforms,
+                              std::vector<Transform3s>& transforms,
                               std::size_t n);
 
 /// @brief Generate n random transforms whose translations are constrained by
@@ -159,8 +159,8 @@ void generateRandomTransforms(CoalScalar extents[6],
 /// translation & rotation to the transforms generated.
 void generateRandomTransforms(CoalScalar extents[6], CoalScalar delta_trans[3],
                               CoalScalar delta_rot,
-                              std::vector<Transform3f>& transforms,
-                              std::vector<Transform3f>& transforms2,
+                              std::vector<Transform3s>& transforms,
+                              std::vector<Transform3s>& transforms2,
                               std::size_t n);
 
 /// @ brief Structure for minimum distance between two meshes and the
@@ -186,7 +186,7 @@ std::string getNodeTypeName(NODE_TYPE node_type);
 
 Quatf makeQuat(CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z);
 
-std::ostream& operator<<(std::ostream& os, const Transform3f& tf);
+std::ostream& operator<<(std::ostream& os, const Transform3s& tf);
 
 /// Get the argument --nb-run from argv
 std::size_t getNbRun(const int& argc, char const* const* argv,