38 #ifndef FCL_CCD_INTERPMOTION_INL_H 39 #define FCL_CCD_INTERPMOTION_INL_H 73 tf1.translation() = T1;
76 tf2.translation() = T2;
108 tf1.translation() = T1;
111 tf2.translation() = T2;
120 template <
typename S>
129 template <
typename S>
141 template <
typename S>
144 return mb_visitor.
visit(*
this);
148 template <
typename S>
151 return mb_visitor.
visit(*
this);
155 template <
typename S>
162 template <
typename S>
174 - (hat_angular_axis * hat_angular_axis).eval() * (cos_model - 1)
183 tm = delta_R *
tf1.linear().eval();
190 template <
typename S>
207 template <
typename S>
214 template <
typename S>
222 template <
typename S>
229 template <
typename S>
236 template <
typename S>
243 template <
typename S>
Quaternion< S > deltaRotation(S dt) const
Eigen::Quaternion< S > Quaternion
template void generateTaylorModelForSinFunc(TaylorModel< double > &tm, double w, double q0)
const Vector3< S > & getLinearVelocity() const
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
template void generateTaylorModelForLinearFunc(TaylorModel< double > &tm, double p, double v)
Eigen::Matrix< S, 3, 3 > Matrix3
Quaternion< S > absoluteRotation(S dt) const
InterpMotion()
Default transformations are all identities.
Eigen::Matrix< S, 3, 1 > Vector3
Eigen::AngleAxis< S > AngleAxis
Transform3< S > tf
The transformation at current time t.
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
Transform3< S > tf1
The transformation at time 0.
S getAngularVelocity() const
const std::shared_ptr< TimeInterval< S > > & getTimeInterval() const
template void generateTaylorModelForCosFunc(TaylorModel< double > &tm, double w, double q0)
bool integrate(S dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
const Vector3< S > & getReferencePoint() const
void getTaylorModel(TMatrix3< S > &tm, TVector3< S > &tv) const
template void hat(Matrix3d &mat, const Vector3d &vec)
Compute the motion bound for a bounding volume, given the closest direction n between two query objec...
virtual S visit(const MotionBase< S > &motion) const
Vector3< S > linear_vel
Linear velocity.
S angular_vel
Angular speed.
const Vector3< S > & getAngularAxis() const
template class FCL_EXPORT InterpMotion< double >
Vector3< S > angular_axis
Angular velocity axis.
virtual S visit(const MotionBase< S > &motion) const =0
Vector3< S > reference_p
Reference point for the motion (in the object's local frame)
Transform3< S > tf2
The transformation at time 1.
S computeMotionBound(const BVMotionBoundVisitor< S > &mb_visitor) const
Compute the motion bound for a bounding volume along a given direction n, which is defined in the vis...
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a t...