38 #ifndef FCL_CCD_INTERPMOTION_INL_H 39 #define FCL_CCD_INTERPMOTION_INL_H 41 #include "fcl/math/motion/interp_motion.h" 48 class InterpMotion<double>;
53 :
MotionBase<S>(), angular_axis(Vector3<S>::UnitX())
66 const Matrix3<S>& R1,
const Vector3<S>& T1,
67 const Matrix3<S>& R2,
const Vector3<S>& T2)
69 tf1(Transform3<S>::Identity()),
70 tf2(Transform3<S>::Identity())
73 tf1.translation() = T1;
76 tf2.translation() = T2;
87 const Transform3<S>& tf1_,
const Transform3<S>& tf2_)
100 const Vector3<S>& T2,
103 tf1(Transform3<S>::Identity()),
104 tf2(Transform3<S>::Identity()),
108 tf1.translation() = T1;
111 tf2.translation() = T2;
120 template <
typename S>
122 const Transform3<S>& tf1_,
const Transform3<S>& tf2_,
const Vector3<S>& O)
129 template <
typename S>
134 tf.linear() = absoluteRotation(dt).toRotationMatrix();
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>
165 Matrix3<S> hat_angular_axis;
169 generateTaylorModelForCosFunc(cos_model,
angular_vel, (S)0);
171 generateTaylorModelForSinFunc(sin_model,
angular_vel, (S)0);
174 - (hat_angular_axis * hat_angular_axis).eval() * (cos_model - 1)
175 + Matrix3<S>::Identity();
177 TaylorModel<S> a(this->getTimeInterval()), b(this->getTimeInterval()), c(this->getTimeInterval());
178 generateTaylorModelForLinearFunc(a, (S)0,
linear_vel[0]);
179 generateTaylorModelForLinearFunc(b, (S)0,
linear_vel[1]);
180 generateTaylorModelForLinearFunc(c, (S)0,
linear_vel[2]);
183 tm = delta_R *
tf1.linear().eval();
190 template <
typename S>
195 const AngleAxis<S> aa(
tf2.linear() *
tf1.linear().transpose());
207 template <
typename S>
214 template <
typename S>
217 Quaternion<S> delta_t = deltaRotation(dt);
218 return delta_t * Quaternion<S>(
tf1.linear());
222 template <
typename S>
229 template <
typename S>
236 template <
typename S>
243 template <
typename S>
Definition: motion_base.h:52
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
Definition: interp_motion-inl.h:156
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular veloc...
Definition: bv_motion_bound_visitor.h:54
InterpMotion()
Default transformations are all identities.
Definition: interp_motion-inl.h:52
Transform3< S > tf
The transformation at current time t.
Definition: interp_motion.h:107
Transform3< S > tf1
The transformation at time 0.
Definition: interp_motion.h:101
Definition: bv_motion_bound_visitor.h:45
Compute the motion bound for a bounding volume, given the closest direction n between two query objec...
Definition: bv_motion_bound_visitor.h:62
Vector3< S > linear_vel
Linear velocity.
Definition: interp_motion.h:110
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...
Definition: interp_motion-inl.h:142
S angular_vel
Angular speed.
Definition: interp_motion.h:113
Definition: taylor_matrix.h:48
bool integrate(double dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
Definition: interp_motion-inl.h:130
Definition: taylor_vector.h:48
Vector3< S > angular_axis
Angular velocity axis.
Definition: interp_motion.h:116
Vector3< S > reference_p
Reference point for the motion (in the object's local frame)
Definition: interp_motion.h:119
Transform3< S > tf2
The transformation at time 1.
Definition: interp_motion.h:104
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a t...
Definition: taylor_model.h:58