orocos_kdl
|
represents both translational and rotational velocities. More...
#include <frames.hpp>
Public Member Functions | |
double & | operator() (int i) |
index-based access to components, first vel(0..2), then rot(3..5) More... | |
double | operator() (int i) const |
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 |
void | ReverseSign () |
Reverses the sign of the twist. More... | |
Twist () | |
The default constructor initialises to Zero via the constructor of Vector. More... | |
Twist (const Vector &_vel, const Vector &_rot) | |
Static Public Member Functions | |
static Twist | Zero () |
Public Attributes | |
Vector | rot |
The rotational velocity of that point. More... | |
Vector | vel |
The velocity of that point. More... | |
Friends | |
double | dot (const Twist &lhs, const Wrench &rhs) |
double | dot (const Wrench &rhs, const Twist &lhs) |
bool | Equal (const Twist &a, const Twist &b, double eps) |
class | Frame |
bool | operator!= (const Twist &a, const Twist &b) |
The literal inequality operator!=(). More... | |
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. More... | |
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. More... | |
Twist | operator* (const Twist &lhs, double rhs) |
Twist | operator* (double lhs, const Twist &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. More... | |
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 723 of file frames.hpp.
|
inline |
The default constructor initialises to Zero via the constructor of Vector.
Definition at line 730 of file frames.hpp.
Definition at line 732 of file frames.hpp.
|
inline |
index-based access to components, first vel(0..2), then rot(3..5)
Definition at line 326 of file frames.inl.
|
inline |
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist
Definition at line 335 of file frames.inl.
Definition at line 319 of file frames.inl.
Definition at line 312 of file frames.inl.
|
inline |
Definition at line 748 of file frames.hpp.
|
inline |
Definition at line 743 of file frames.hpp.
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 302 of file frames.inl.
|
inline |
Reverses the sign of the twist.
Definition at line 296 of file frames.inl.
|
inlinestatic |
Definition at line 290 of file frames.inl.
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 |
Definition at line 793 of file frames.hpp.
The literal inequality operator!=().
Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point.
Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point.
The literal equality operator==(), also identical.
|
friend |
Definition at line 792 of file frames.hpp.
|
friend |
Vector KDL::Twist::rot |
The rotational velocity of that point.
Definition at line 726 of file frames.hpp.
Vector KDL::Twist::vel |
The velocity of that point.
Definition at line 725 of file frames.hpp.