Public Member Functions | Protected Member Functions | Protected Attributes
fcl::ScrewMotion Class Reference

#include <hpp/fcl/ccd/motion.h>

Inheritance diagram for fcl::ScrewMotion:
[legend]
Collaboration diagram for fcl::ScrewMotion:
[legend]

List of all members.

Public Member Functions

 ScrewMotion ()
 Default transformations are all identities.
 ScrewMotion (const Matrix3f &R1, const Vec3f &T1, const Matrix3f &R2, const Vec3f &T2)
 Construct motion from the initial rotation/translation and goal rotation/translation.
 ScrewMotion (const Transform3f &tf1_, const Transform3f &tf2_)
 Construct motion from the initial transform and goal transform.
bool integrate (double dt) const
 Integrate the motion from 0 to dt We compute the current transformation from zero point instead of from last integrate time, for precision.
FCL_REAL computeMotionBound (const BVMotionBoundVisitor &mb_visitor) const
 Compute the motion bound for a bounding volume along a given direction n, which is defined in the visitor.
FCL_REAL computeMotionBound (const TriangleMotionBoundVisitor &mb_visitor) const
 Compute the motion bound for a triangle along a given direction n, which is defined in the visitor.
void getCurrentTransform (Transform3f &tf_) const
 Get the rotation and translation in current step.
void getTaylorModel (TMatrix3 &tm, TVector3 &tv) const
FCL_REAL getLinearVelocity () const
FCL_REAL getAngularVelocity () const
const Vec3fgetAxis () const
const Vec3fgetAxisOrigin () const

Protected Member Functions

void computeScrewParameter ()
Quaternion3f deltaRotation (FCL_REAL dt) const
Quaternion3f absoluteRotation (FCL_REAL dt) const

Protected Attributes

Transform3f tf1
 The transformation at time 0.
Transform3f tf2
 The transformation at time 1.
Transform3f tf
 The transformation at current time t.
Vec3f axis
 screw axis
Vec3f p
 A point on the axis S.
FCL_REAL linear_vel
 linear velocity along the axis
FCL_REAL angular_vel
 angular velocity

Constructor & Destructor Documentation

fcl::ScrewMotion::ScrewMotion ( ) [inline]

Default transformations are all identities.

References angular_vel, axis, linear_vel, and fcl::Vec3fX< T >::setValue().

fcl::ScrewMotion::ScrewMotion ( const Matrix3f R1,
const Vec3f T1,
const Matrix3f R2,
const Vec3f T2 
) [inline]

Construct motion from the initial rotation/translation and goal rotation/translation.

References computeScrewParameter().

fcl::ScrewMotion::ScrewMotion ( const Transform3f tf1_,
const Transform3f tf2_ 
) [inline]

Construct motion from the initial transform and goal transform.

References computeScrewParameter().


Member Function Documentation

Quaternion3f fcl::ScrewMotion::absoluteRotation ( FCL_REAL  dt) const [inline, protected]
FCL_REAL fcl::ScrewMotion::computeMotionBound ( const BVMotionBoundVisitor mb_visitor) const [inline, virtual]

Compute the motion bound for a bounding volume along a given direction n, which is defined in the visitor.

Implements fcl::MotionBase.

References fcl::BVMotionBoundVisitor::visit().

FCL_REAL fcl::ScrewMotion::computeMotionBound ( const TriangleMotionBoundVisitor mb_visitor) const [inline, virtual]

Compute the motion bound for a triangle along a given direction n, which is defined in the visitor.

Implements fcl::MotionBase.

References fcl::TriangleMotionBoundVisitor::visit().

void fcl::ScrewMotion::computeScrewParameter ( ) [inline, protected]
Quaternion3f fcl::ScrewMotion::deltaRotation ( FCL_REAL  dt) const [inline, protected]
FCL_REAL fcl::ScrewMotion::getAngularVelocity ( ) const [inline]

References angular_vel.

const Vec3f& fcl::ScrewMotion::getAxis ( ) const [inline]

References axis.

const Vec3f& fcl::ScrewMotion::getAxisOrigin ( ) const [inline]

References p.

void fcl::ScrewMotion::getCurrentTransform ( Transform3f tf_) const [inline, virtual]

Get the rotation and translation in current step.

Implements fcl::MotionBase.

References tf.

FCL_REAL fcl::ScrewMotion::getLinearVelocity ( ) const [inline]

References linear_vel.

void fcl::ScrewMotion::getTaylorModel ( TMatrix3 tm,
TVector3 tv 
) const [inline, virtual]
bool fcl::ScrewMotion::integrate ( double  dt) const [inline, virtual]

Integrate the motion from 0 to dt We compute the current transformation from zero point instead of from last integrate time, for precision.

Implements fcl::MotionBase.

References absoluteRotation(), axis, deltaRotation(), fcl::Transform3f::getTranslation(), linear_vel, p, fcl::Transform3f::setQuatRotation(), fcl::Transform3f::setTranslation(), tf, tf1, and fcl::Quaternion3f::transform().


Member Data Documentation

linear velocity along the axis

Referenced by computeScrewParameter(), getLinearVelocity(), getTaylorModel(), integrate(), and ScrewMotion().

A point on the axis S.

Referenced by computeScrewParameter(), getAxisOrigin(), getTaylorModel(), and integrate().

Transform3f fcl::ScrewMotion::tf [mutable, protected]

The transformation at current time t.

Referenced by getCurrentTransform(), and integrate().

The transformation at time 0.

Referenced by absoluteRotation(), computeScrewParameter(), getTaylorModel(), and integrate().

The transformation at time 1.

Referenced by computeScrewParameter().

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines