Go to the documentation of this file.
   38 #ifndef FCL_CCD_SCREWMOTION_INL_H 
   39 #define FCL_CCD_SCREWMOTION_INL_H 
   74   tf1.translation() = T1;
 
   77   tf2.translation() = T2;
 
   88   : tf1(tf1_), tf2(tf2_), tf(tf1)
 
   99   tf.linear() = absoluteRotation(dt).toRotationMatrix();
 
  102   tf.translation() = p + axis * (dt * linear_vel) + delta_rot * (tf1.translation() - p);
 
  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)
 
  147   TaylorModel<S> a(this->getTimeInterval()), b(this->getTimeInterval()), c(this->getTimeInterval());
 
  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());
 
  164   angular_vel = aa.angle();
 
  168     angular_vel = -angular_vel;
 
  172   if(angular_vel < 1e-10)
 
  175     axis = tf2.translation() - tf1.translation();
 
  176     linear_vel = axis.norm();
 
  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;
 
  183     linear_vel = o.dot(axis);
 
  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
Quaternion< S > absoluteRotation(S dt) const
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
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...
template void generateTaylorModelForLinearFunc(TaylorModel< double > &tm, double p, double v)
Transform3< S > tf2
The transformation at time 1.
Eigen::Quaternion< S > Quaternion
S linear_vel
linear velocity along the axis
const Vector3< S > & getAxisOrigin() const
template void generateTaylorModelForSinFunc(TaylorModel< double > &tm, double w, double q0)
Transform3< S > tf
The transformation at current time t.
ScrewMotion()
Default transformations are all identities.
S getLinearVelocity() const
const Vector3< S > & getAxis() const
Eigen::AngleAxis< S > AngleAxis
virtual S visit(const MotionBase< S > &motion) const =0
Eigen::Matrix< S, 3, 1 > Vector3
template class FCL_EXPORT ScrewMotion< double >
Eigen::Matrix< S, 3, 3 > Matrix3
void computeScrewParameter()
virtual S visit(const MotionBase< S > &motion) const
template void generateTaylorModelForCosFunc(TaylorModel< double > &tm, double w, double q0)
Transform3< S > tf1
The transformation at time 0.
S angular_vel
angular velocity
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a t...
Compute the motion bound for a bounding volume, given the closest direction n between two query objec...
bool integrate(S dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
template void hat(Matrix3d &mat, const Vector3d &vec)
void getTaylorModel(TMatrix3< S > &tm, TVector3< S > &tv) const
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
S getAngularVelocity() const
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:18