38 #ifndef FCL_CCD_INTERPMOTION_H 39 #define FCL_CCD_INTERPMOTION_H 58 class FCL_EXPORT InterpMotion :
public MotionBase<S>
65 InterpMotion(
const Matrix3<S>& R1,
const Vector3<S>& T1,
66 const Matrix3<S>& R2,
const Vector3<S>& T2);
68 InterpMotion(
const Transform3<S>& tf1_,
const Transform3<S>& tf2_);
71 InterpMotion(
const Matrix3<S>& R1,
const Vector3<S>& T1,
72 const Matrix3<S>& R2,
const Vector3<S>& T2,
75 InterpMotion(
const Transform3<S>& tf1_,
const Transform3<S>& tf2_,
const Vector3<S>& O);
79 bool integrate(S dt)
const;
82 S computeMotionBound(
const BVMotionBoundVisitor<S>& mb_visitor)
const;
85 S computeMotionBound(
const TriangleMotionBoundVisitor<S>& mb_visitor)
const;
88 void getCurrentTransform(Transform3<S>& tf_)
const;
90 void getTaylorModel(TMatrix3<S>& tm, TVector3<S>& tv)
const;
94 void computeVelocity();
96 Quaternion<S> deltaRotation(S dt)
const;
98 Quaternion<S> absoluteRotation(S dt)
const;
126 S getAngularVelocity()
const;
130 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Eigen::Matrix< S, 3, 1 > Vector3
Transform3< S > tf
The transformation at current time t.
Transform3< S > tf1
The transformation at time 0.
Vector3< S > linear_vel
Linear velocity.
S angular_vel
Angular speed.
Vector3< S > angular_axis
Angular velocity axis.
Vector3< S > reference_p
Reference point for the motion (in the object's local frame)
Transform3< S > tf2
The transformation at time 1.