38 #ifndef FCL_CCD_SCREWMOTION_INL_H 39 #define FCL_CCD_SCREWMOTION_INL_H 74 tf1.translation() = T1;
77 tf2.translation() = T2;
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>
144 - (hat_axis * hat_axis).eval() * (cos_model - 1)
153 tm = delta_R *
tf1.linear().eval();
154 tv = delta_R *
tf1.translation().eval() + delta_T;
158 template <
typename S>
175 axis =
tf2.translation() -
tf1.translation();
177 p =
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>
204 template <
typename S>
211 template <
typename S>
218 template <
typename S>
225 template <
typename S>
Quaternion< S > deltaRotation(S dt) const
S angular_vel
angular velocity
Vector3< S > p
A point on the axis.
Eigen::Quaternion< S > Quaternion
template void generateTaylorModelForSinFunc(TaylorModel< double > &tm, double w, double q0)
ScrewMotion()
Default transformations are all identities.
S getAngularVelocity() const
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
template void generateTaylorModelForLinearFunc(TaylorModel< double > &tm, double p, double v)
S linear_vel
linear velocity along the axis
Vector3< S > axis
screw axis
Transform3< S > tf
The transformation at current time t.
template class FCL_EXPORT ScrewMotion< double >
Eigen::Matrix< S, 3, 3 > Matrix3
Eigen::Matrix< S, 3, 1 > Vector3
const Vector3< S > & getAxis() const
Eigen::AngleAxis< S > AngleAxis
Transform3< S > tf2
The transformation at time 1.
bool integrate(S dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
const std::shared_ptr< TimeInterval< S > > & getTimeInterval() const
template void generateTaylorModelForCosFunc(TaylorModel< double > &tm, double w, double q0)
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...
Quaternion< S > absoluteRotation(S dt) const
virtual S visit(const MotionBase< S > &motion) const
const Vector3< S > & getAxisOrigin() const
void computeScrewParameter()
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
Transform3< S > tf1
The transformation at time 0.
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...
virtual S visit(const MotionBase< S > &motion) const =0
S getLinearVelocity() const
void getTaylorModel(TMatrix3< S > &tm, TVector3< S > &tv) const
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a t...