38 #ifndef FCL_CCD_SCREWMOTION_H 39 #define FCL_CCD_SCREWMOTION_H 52 class FCL_EXPORT ScrewMotion :
public MotionBase<S>
59 ScrewMotion(
const Matrix3<S>& R1,
const Vector3<S>& T1,
60 const Matrix3<S>& R2,
const Vector3<S>& T2);
63 ScrewMotion(
const Transform3<S>& tf1_,
64 const Transform3<S>& tf2_);
68 bool integrate(S dt)
const;
71 S computeMotionBound(
const BVMotionBoundVisitor<S>& mb_visitor)
const;
74 S computeMotionBound(
const TriangleMotionBoundVisitor<S>& mb_visitor)
const;
77 void getCurrentTransform(Transform3<S>& tf_)
const;
79 void getTaylorModel(TMatrix3<S>& tm, TVector3<S>& tv)
const;
82 void computeScrewParameter();
84 Quaternion<S> deltaRotation(S dt)
const;
86 Quaternion<S> absoluteRotation(S dt)
const;
111 S getLinearVelocity()
const;
113 S getAngularVelocity()
const;
119 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
S angular_vel
angular velocity
Vector3< S > p
A point on the axis.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
S linear_vel
linear velocity along the axis
Vector3< S > axis
screw axis
Transform3< S > tf
The transformation at current time t.
Eigen::Matrix< S, 3, 1 > Vector3
Transform3< S > tf2
The transformation at time 1.
Transform3< S > tf1
The transformation at time 0.