represents both translational and rotational velocities. More...
#include <src/frames.hpp>

Public Member Functions | |
| Twist () | |
| The default constructor initialises to Zero via the constructor of Vector. | |
| Twist (const Vector &_vel, const Vector &_rot) | |
| Twist & | operator-= (const Twist &arg) |
| Twist & | operator+= (const Twist &arg) |
| double & | operator() (int i) |
| index-based access to components, first vel(0..2), then rot(3..5) | |
| 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 index) const |
| double & | operator[] (int index) |
| void | ReverseSign () |
| Reverses the sign of the twist. | |
| Twist | RefPoint (const Vector &v_base_AB) const |
| Changes the reference point of the twist. | |
Static Public Member Functions | |
| static Twist | Zero () |
Public Attributes | |
| Vector | vel |
| The velocity of that point. | |
| Vector | rot |
| The rotational velocity of that point. | |
Friends | |
| class | Rotation |
| class | Frame |
| Twist | operator* (const Twist &lhs, double rhs) |
| 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 &lhs, const Twist &rhs) |
| Twist | operator- (const Twist &arg) |
| double | dot (const Twist &lhs, const Wrench &rhs) |
| double | dot (const Wrench &rhs, const Twist &lhs) |
| void | SetToZero (Twist &v) |
| 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. | |
| 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. | |
| bool | Equal (const Twist &a, const Twist &b, double eps=epsilon) |
| do not use operator == because the definition of Equal(.,. | |
| bool | operator== (const Twist &a, const Twist &b) |
| The literal equality operator==(), also identical. | |
| bool | operator!= (const Twist &a, const Twist &b) |
| The literal inequality operator!=(). | |
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.
| KDL::Twist::Twist | ( | ) | [inline] |
The default constructor initialises to Zero via the constructor of Vector.
| 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
| double & KDL::Twist::operator() | ( | int | i | ) | [inline] |
index-based access to components, first vel(0..2), then rot(3..5)
Referenced by operator[]().
| double& KDL::Twist::operator[] | ( | int | index | ) | [inline] |
References operator()().
| double KDL::Twist::operator[] | ( | int | index | ) | const [inline] |
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
Referenced by KDL::Jacobian::changeRefPoint(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Segment::twist().
| void KDL::Twist::ReverseSign | ( | ) | [inline] |
Reverses the sign of the twist.
| Twist KDL::Twist::Zero | ( | ) | [inline, static] |
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] |
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] |
| void SetToZero | ( | Twist & | v | ) | [friend] |
The rotational velocity of that point.
Referenced by KDL::operator*(), KDL::Path_Line::Path_Line(), and KDL::Jacobian::setColumn().
The velocity of that point.
Referenced by KDL::operator*(), KDL::Path_Line::Path_Line(), and KDL::Jacobian::setColumn().
1.6.3