Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular velocity The motion is R(t)(p - p_ref) + p_ref + T(t) Therefore, R(0) = R0, R(1) = R1 T(0) = T0 + R0 p_ref - p_ref T(1) = T1 + R1 p_ref - p_ref. More...
#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... | |
| const Vector3< S > & | getAngularAxis () const | 
| S | getAngularVelocity () const | 
| void | getCurrentTransform (Transform3< S > &tf_) const | 
| Get the rotation and translation in current step.  More... | |
| const Vector3< S > & | getLinearVelocity () const | 
| const Vector3< S > & | getReferencePoint () 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... | |
| InterpMotion () | |
| Default transformations are all identities.  More... | |
| InterpMotion (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... | |
| InterpMotion (const Matrix3< S > &R1, const Vector3< S > &T1, const Matrix3< S > &R2, const Vector3< S > &T2, const Vector3< S > &O) | |
| Construct motion from the initial rotation/translation and goal rotation/translation related to some rotation center.  More... | |
| InterpMotion (const Transform3< S > &tf1_, const Transform3< S > &tf2_) | |
| InterpMotion (const Transform3< S > &tf1_, const Transform3< S > &tf2_, const Vector3< S > &O) | |
| Protected Member Functions | |
| Quaternion< S > | absoluteRotation (S dt) const | 
| void | computeVelocity () | 
| Quaternion< S > | deltaRotation (S dt) const | 
| Protected Attributes | |
| Vector3< S > | angular_axis | 
| Angular velocity axis.  More... | |
| S | angular_vel | 
| Angular speed.  More... | |
| Vector3< S > | linear_vel | 
| Linear velocity.  More... | |
| Vector3< S > | reference_p | 
| Reference point for the motion (in the object's local frame)  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... | |
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular velocity The motion is R(t)(p - p_ref) + p_ref + T(t) Therefore, R(0) = R0, R(1) = R1 T(0) = T0 + R0 p_ref - p_ref T(1) = T1 + R1 p_ref - p_ref.
Definition at line 54 of file bv_motion_bound_visitor.h.
| fcl::InterpMotion< S >::InterpMotion | 
Default transformations are all identities.
Definition at line 52 of file interp_motion-inl.h.
| fcl::InterpMotion< S >::InterpMotion | ( | 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 65 of file interp_motion-inl.h.
| fcl::InterpMotion< S >::InterpMotion | ( | const Transform3< S > & | tf1_, | 
| const Transform3< S > & | tf2_ | ||
| ) | 
Definition at line 86 of file interp_motion-inl.h.
| fcl::InterpMotion< S >::InterpMotion | ( | const Matrix3< S > & | R1, | 
| const Vector3< S > & | T1, | ||
| const Matrix3< S > & | R2, | ||
| const Vector3< S > & | T2, | ||
| const Vector3< S > & | O | ||
| ) | 
Construct motion from the initial rotation/translation and goal rotation/translation related to some rotation center.
Definition at line 96 of file interp_motion-inl.h.
| fcl::InterpMotion< S >::InterpMotion | ( | const Transform3< S > & | tf1_, | 
| const Transform3< S > & | tf2_, | ||
| const Vector3< S > & | O | ||
| ) | 
Definition at line 121 of file interp_motion-inl.h.
| 
 | protected | 
Definition at line 215 of file interp_motion-inl.h.
| S fcl::InterpMotion< 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 142 of file interp_motion-inl.h.
| S fcl::InterpMotion< 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 149 of file interp_motion-inl.h.
| 
 | protected | 
Definition at line 191 of file interp_motion-inl.h.
| 
 | protected | 
Definition at line 208 of file interp_motion-inl.h.
| const Vector3< S > & fcl::InterpMotion< S >::getAngularAxis | 
Definition at line 230 of file interp_motion-inl.h.
| S fcl::InterpMotion< S >::getAngularVelocity | 
Definition at line 237 of file interp_motion-inl.h.
| void fcl::InterpMotion< S >::getCurrentTransform | ( | Transform3< S > & | tf_ | ) | const | 
Get the rotation and translation in current step.
Definition at line 156 of file interp_motion-inl.h.
| const Vector3< S > & fcl::InterpMotion< S >::getLinearVelocity | 
Definition at line 244 of file interp_motion-inl.h.
| const Vector3< S > & fcl::InterpMotion< S >::getReferencePoint | 
Definition at line 223 of file interp_motion-inl.h.
| void fcl::InterpMotion< S >::getTaylorModel | ( | TMatrix3< S > & | tm, | 
| TVector3< S > & | tv | ||
| ) | const | 
Definition at line 163 of file interp_motion-inl.h.
| bool fcl::InterpMotion< 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 130 of file interp_motion-inl.h.
| 
 | protected | 
Angular velocity axis.
Definition at line 116 of file interp_motion.h.
| 
 | protected | 
Angular speed.
Definition at line 113 of file interp_motion.h.
| 
 | protected | 
Linear velocity.
Definition at line 110 of file interp_motion.h.
| 
 | protected | 
Reference point for the motion (in the object's local frame)
Definition at line 119 of file interp_motion.h.
| 
 | mutableprotected | 
The transformation at current time t.
Definition at line 107 of file interp_motion.h.
| 
 | protected | 
The transformation at time 0.
Definition at line 101 of file interp_motion.h.
| 
 | protected | 
The transformation at time 1.
Definition at line 104 of file interp_motion.h.