#include <bv_motion_bound_visitor.h>
| Public Member Functions | |
| 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 visitor.  More... | |
| S | computeMotionBound (const TriangleMotionBoundVisitor< S > &mb_visitor) const | 
| Compute the motion bound for a triangle along a given direction n, which is defined in the visitor.  More... | |
| S | getAngularVelocity () const | 
| const Vector3< S > & | getAxis () const | 
| const Vector3< S > & | getAxisOrigin () const | 
| void | getCurrentTransform (Transform3< S > &tf_) const | 
| Get the rotation and translation in current step.  More... | |
| S | getLinearVelocity () const | 
| void | getTaylorModel (TMatrix3< S > &tm, TVector3< S > &tv) const | 
| bool | integrate (S 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.  More... | |
| ScrewMotion () | |
| Default transformations are all identities.  More... | |
| ScrewMotion (const Matrix3< S > &R1, const Vector3< S > &T1, const Matrix3< S > &R2, const Vector3< S > &T2) | |
| Construct motion from the initial rotation/translation and goal rotation/translation.  More... | |
| ScrewMotion (const Transform3< S > &tf1_, const Transform3< S > &tf2_) | |
| Construct motion from the initial transform and goal transform.  More... | |
| Protected Member Functions | |
| Quaternion< S > | absoluteRotation (S dt) const | 
| void | computeScrewParameter () | 
| Quaternion< S > | deltaRotation (S dt) const | 
| Protected Attributes | |
| S | angular_vel | 
| angular velocity  More... | |
| Vector3< S > | axis | 
| screw axis  More... | |
| S | linear_vel | 
| linear velocity along the axis  More... | |
| Vector3< S > | p | 
| A point on the axis.  More... | |
| Transform3< S > | tf | 
| The transformation at current time t.  More... | |
| Transform3< S > | tf1 | 
| The transformation at time 0.  More... | |
| Transform3< S > | tf2 | 
| The transformation at time 1.  More... | |
Definition at line 51 of file bv_motion_bound_visitor.h.
| fcl::ScrewMotion< S >::ScrewMotion | 
Default transformations are all identities.
Definition at line 52 of file screw_motion-inl.h.
| fcl::ScrewMotion< S >::ScrewMotion | ( | const Matrix3< S > & | R1, | 
| const Vector3< S > & | T1, | ||
| const Matrix3< S > & | R2, | ||
| const Vector3< S > & | T2 | ||
| ) | 
Construct motion from the initial rotation/translation and goal rotation/translation.
Definition at line 66 of file screw_motion-inl.h.
| fcl::ScrewMotion< S >::ScrewMotion | ( | const Transform3< S > & | tf1_, | 
| const Transform3< S > & | tf2_ | ||
| ) | 
Construct motion from the initial transform and goal transform.
Definition at line 86 of file screw_motion-inl.h.
| 
 | protected | 
Definition at line 196 of file screw_motion-inl.h.
| S fcl::ScrewMotion< 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 visitor.
Definition at line 109 of file screw_motion-inl.h.
| S fcl::ScrewMotion< S >::computeMotionBound | ( | const TriangleMotionBoundVisitor< S > & | mb_visitor | ) | const | 
Compute the motion bound for a triangle along a given direction n, which is defined in the visitor.
Definition at line 117 of file screw_motion-inl.h.
| 
 | protected | 
Definition at line 159 of file screw_motion-inl.h.
| 
 | protected | 
Definition at line 189 of file screw_motion-inl.h.
| S fcl::ScrewMotion< S >::getAngularVelocity | 
Definition at line 212 of file screw_motion-inl.h.
| const Vector3< S > & fcl::ScrewMotion< S >::getAxis | 
Definition at line 219 of file screw_motion-inl.h.
| const Vector3< S > & fcl::ScrewMotion< S >::getAxisOrigin | 
Definition at line 226 of file screw_motion-inl.h.
| void fcl::ScrewMotion< S >::getCurrentTransform | ( | Transform3< S > & | tf_ | ) | const | 
Get the rotation and translation in current step.
Definition at line 125 of file screw_motion-inl.h.
| S fcl::ScrewMotion< S >::getLinearVelocity | 
Definition at line 205 of file screw_motion-inl.h.
| void fcl::ScrewMotion< S >::getTaylorModel | ( | TMatrix3< S > & | tm, | 
| TVector3< S > & | tv | ||
| ) | const | 
Definition at line 132 of file screw_motion-inl.h.
| bool fcl::ScrewMotion< S >::integrate | ( | S | 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.
Definition at line 95 of file screw_motion-inl.h.
| 
 | protected | 
angular velocity
Definition at line 107 of file screw_motion.h.
| 
 | protected | 
screw axis
Definition at line 98 of file screw_motion.h.
| 
 | protected | 
linear velocity along the axis
Definition at line 104 of file screw_motion.h.
| 
 | protected | 
A point on the axis.
Definition at line 101 of file screw_motion.h.
| 
 | mutableprotected | 
The transformation at current time t.
Definition at line 95 of file screw_motion.h.
| 
 | protected | 
The transformation at time 0.
Definition at line 89 of file screw_motion.h.
| 
 | protected | 
The transformation at time 1.
Definition at line 92 of file screw_motion.h.