represents both translational and rotational velocities. More...
#include <frames.hpp>
Public Member Functions | |
| double | operator() (int i) const | 
| index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist   | |
| double & | operator() (int i) | 
| index-based access to components, first vel(0..2), then rot(3..5)   | |
| Twist & | operator+= (const Twist &arg) | 
| Twist & | operator-= (const Twist &arg) | 
| double & | operator[] (int index) | 
| double | operator[] (int index) const | 
| Twist | RefPoint (const Vector &v_base_AB) const | 
| Changes the reference point of the twist.   | |
| void | ReverseSign () | 
| Reverses the sign of the twist.   | |
| Twist (const Vector &_vel, const Vector &_rot) | |
| Twist () | |
| The default constructor initialises to Zero via the constructor of Vector.   | |
Static Public Member Functions | |
| static Twist | Zero () | 
Public Attributes | |
| Vector | rot | 
| The rotational velocity of that point.   | |
| Vector | vel | 
| The velocity of that point.   | |
Friends | |
| double | dot (const Wrench &rhs, const Twist &lhs) | 
| double | dot (const Twist &lhs, const Wrench &rhs) | 
| bool | Equal (const Twist &a, const Twist &b, double eps=epsilon) | 
| do not use operator == because the definition of Equal(.,.   | |
| class | Frame | 
| bool | operator!= (const Twist &a, const Twist &b) | 
| The literal inequality operator!=().   | |
| Wrench | operator* (const Twist &lhs, const Wrench &rhs) | 
| Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point.   | |
| Twist | operator* (const Twist &lhs, const Twist &rhs) | 
| Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point.   | |
| Twist | operator* (double lhs, const Twist &rhs) | 
| Twist | operator* (const Twist &lhs, double rhs) | 
| Twist | operator+ (const Twist &lhs, const Twist &rhs) | 
| Twist | operator- (const Twist &arg) | 
| Twist | operator- (const Twist &lhs, const Twist &rhs) | 
| Twist | operator/ (const Twist &lhs, double rhs) | 
| bool | operator== (const Twist &a, const Twist &b) | 
| The literal equality operator==(), also identical.   | |
| class | Rotation | 
| void | SetToZero (Twist &v) | 
represents both translational and rotational velocities.
This class represents a twist. A twist is the combination of translational velocity and rotational velocity applied at one point.
Definition at line 668 of file frames.hpp.
| KDL::Twist::Twist | ( | ) |  [inline] | 
        
The default constructor initialises to Zero via the constructor of Vector.
Definition at line 675 of file frames.hpp.
Referenced by Zero().
Definition at line 677 of file frames.hpp.
| double KDL::Twist::operator() | ( | int | i | ) |  const [inline] | 
        
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist
Definition at line 330 of file frames.inl.
| double & KDL::Twist::operator() | ( | int | i | ) |  [inline] | 
        
index-based access to components, first vel(0..2), then rot(3..5)
Definition at line 321 of file frames.inl.
Referenced by operator[]().
Definition at line 314 of file frames.inl.
Definition at line 307 of file frames.inl.
| double& KDL::Twist::operator[] | ( | int | index | ) |  [inline] | 
        
Definition at line 693 of file frames.hpp.
References operator()().
| double KDL::Twist::operator[] | ( | int | index | ) |  const [inline] | 
        
Definition at line 688 of file frames.hpp.
References operator()().
Changes the reference point of the twist.
The vector v_base_AB is expressed in the same base as the twist The vector v_base_AB is a vector from the old point to the new point.
Complexity : 6M+6A
Definition at line 297 of file frames.inl.
Referenced by KDL::Jacobian::changeRefPoint(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Segment::twist().
| void KDL::Twist::ReverseSign | ( | ) |  [inline] | 
        
Reverses the sign of the twist.
Definition at line 291 of file frames.inl.
References KDL::Vector::ReverseSign(), rot, and vel.
| Twist KDL::Twist::Zero | ( | ) |  [inline, static] | 
        
Definition at line 285 of file frames.inl.
References Twist(), and KDL::Vector::Zero().
Referenced by KDL::Trajectory_Stationary::Acc(), KDL::Path_Point::Acc(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::TreeIkSolverPos_NR_JL::TreeIkSolverPos_NR_JL(), KDL::Joint::twist(), KDL::Trajectory_Stationary::Vel(), and KDL::Path_Point::Vel().
do not use operator == because the definition of Equal(.,.
) is slightly different. It compares whether the 2 arguments are equal in an eps-interval
friend class Frame [friend] | 
        
Definition at line 738 of file frames.hpp.
The literal inequality operator!=().
Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point.
Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point.
The literal equality operator==(), also identical.
friend class Rotation [friend] | 
        
Definition at line 737 of file frames.hpp.
| void SetToZero | ( | Twist & | v | ) |  [friend] | 
        
The rotational velocity of that point.
Definition at line 671 of file frames.hpp.
Referenced by KDL::addDelta(), KDL::diff(), KDL::dot(), KDL::Equal(), KDL::Frame::Integrate(), KDL::FrameVel::Inverse(), KDL::RotationVel::Inverse(), KDL::Frame::Inverse(), KDL::Rotation::Inverse(), KDL::FrameAcc::Inverse(), KDL::RotationAcc::Inverse(), operator()(), KDL::FrameVel::operator*(), KDL::RotationVel::operator*(), KDL::Frame::operator*(), KDL::FrameAcc::operator*(), KDL::RotationAcc::operator*(), KDL::operator*(), KDL::operator+(), operator+=(), KDL::operator-(), operator-=(), KDL::operator/(), KDL::operator==(), KDL::Path_Line::Path_Line(), KDL::posrandom(), KDL::random(), ReverseSign(), KDL::Jacobian::setColumn(), and KDL::SetToZero().
The velocity of that point.
Definition at line 670 of file frames.hpp.
Referenced by KDL::addDelta(), KDL::diff(), KDL::dot(), KDL::Equal(), KDL::Frame::Integrate(), KDL::FrameVel::Inverse(), KDL::RotationVel::Inverse(), KDL::Frame::Inverse(), KDL::Rotation::Inverse(), KDL::FrameAcc::Inverse(), KDL::RotationAcc::Inverse(), operator()(), KDL::FrameVel::operator*(), KDL::RotationVel::operator*(), KDL::Frame::operator*(), KDL::FrameAcc::operator*(), KDL::RotationAcc::operator*(), KDL::operator*(), KDL::operator+(), operator+=(), KDL::operator-(), operator-=(), KDL::operator/(), KDL::operator==(), KDL::Path_Line::Path_Line(), KDL::posrandom(), KDL::random(), ReverseSign(), KDL::Jacobian::setColumn(), and KDL::SetToZero().
 1.6.1