38 #ifndef FCL_CCD_SCREWMOTION_INL_H 39 #define FCL_CCD_SCREWMOTION_INL_H 41 #include "fcl/math/motion/screw_motion.h" 48 class ScrewMotion<double>;
67 const Matrix3<S>& R1,
const Vector3<S>& T1,
68 const Matrix3<S>& R2,
const Vector3<S>& T2)
70 tf1(Transform3<S>::Identity()),
71 tf2(Transform3<S>::Identity())
74 tf1.translation() = T1;
77 tf2.translation() = T2;
81 computeScrewParameter();
87 const Transform3<S>& tf1_,
const Transform3<S>& tf2_)
90 computeScrewParameter();
99 tf.linear() = absoluteRotation(dt).toRotationMatrix();
101 Quaternion<S> delta_rot = deltaRotation(dt);
108 template <
typename S>
112 return mb_visitor.visit(*
this);
116 template <
typename S>
120 return mb_visitor.visit(*
this);
124 template <
typename S>
131 template <
typename S>
138 generateTaylorModelForCosFunc(cos_model,
angular_vel, (S)0);
141 generateTaylorModelForSinFunc(sin_model,
angular_vel, (S)0);
144 - (hat_axis * hat_axis).eval() * (cos_model - 1)
145 + Matrix3<S>::Identity();
147 TaylorModel<S> a(this->getTimeInterval()), b(this->getTimeInterval()), c(this->getTimeInterval());
149 generateTaylorModelForLinearFunc(b, (S)0,
linear_vel * axis[1]);
150 generateTaylorModelForLinearFunc(c, (S)0,
linear_vel * axis[2]);
153 tm = delta_R *
tf1.linear().eval();
154 tv = delta_R *
tf1.translation().eval() + delta_T;
158 template <
typename S>
161 const AngleAxis<S> aa(
tf2.linear() *
tf1.linear().transpose());
175 axis =
tf2.translation() -
tf1.translation();
177 p =
tf1.translation();
181 Vector3<S> o =
tf2.translation() -
tf1.translation();
182 p = (
tf1.translation() +
tf2.translation() + axis.cross(o) * (1.0 / tan(
angular_vel / 2.0))) * 0.5;
188 template <
typename S>
195 template <
typename S>
198 Quaternion<S> delta_t = deltaRotation(dt);
200 return delta_t * Quaternion<S>(
tf1.linear());
204 template <
typename S>
211 template <
typename S>
218 template <
typename S>
225 template <
typename S>
S angular_vel
angular velocity
Definition: screw_motion.h:107
Definition: motion_base.h:52
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
Vector3< S > p
A point on the axis.
Definition: screw_motion.h:101
Definition: bv_motion_bound_visitor.h:51
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
Definition: screw_motion-inl.h:125
ScrewMotion()
Default transformations are all identities.
Definition: screw_motion-inl.h:52
S linear_vel
linear velocity along the axis
Definition: screw_motion.h:104
Vector3< S > axis
screw axis
Definition: screw_motion.h:98
Transform3< S > tf
The transformation at current time t.
Definition: screw_motion.h:95
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: screw_motion-inl.h:109
Transform3< S > tf2
The transformation at time 1.
Definition: screw_motion.h:92
bool integrate(double dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
Definition: screw_motion-inl.h:95
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
Definition: taylor_matrix.h:48
Transform3< S > tf1
The transformation at time 0.
Definition: screw_motion.h:89
Definition: taylor_vector.h:48
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a t...
Definition: taylor_model.h:58