38 #ifndef FCL_CONTINUOUS_COLLISION_H 39 #define FCL_CONTINUOUS_COLLISION_H 56 const CollisionGeometry<S>* o1,
57 const MotionBase<S>* motion1,
58 const CollisionGeometry<S>* o2,
59 const MotionBase<S>* motion2,
60 const ContinuousCollisionRequest<S>& request,
61 ContinuousCollisionResult<S>& result);
66 const CollisionGeometry<S>* o1,
67 const Transform3<S>& tf1_beg,
68 const Transform3<S>& tf1_end,
69 const CollisionGeometry<S>* o2,
70 const Transform3<S>& tf2_beg,
71 const Transform3<S>& tf2_end,
72 const ContinuousCollisionRequest<S>& request,
73 ContinuousCollisionResult<S>& result);
78 const CollisionObject<S>* o1,
79 const Transform3<S>& tf1_end,
80 const CollisionObject<S>* o2,
81 const Transform3<S>& tf2_end,
82 const ContinuousCollisionRequest<S>& request,
83 ContinuousCollisionResult<S>& result);
88 const ContinuousCollisionObject<S>* o1,
89 const ContinuousCollisionObject<S>* o2,
90 const ContinuousCollisionRequest<S>& request,
91 ContinuousCollisionResult<S>& result);
template double continuousCollide(const CollisionGeometry< double > *o1, const MotionBase< double > *motion1, const CollisionGeometry< double > *o2, const MotionBase< double > *motion2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result)
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)