KDL  1.3.0
Public Member Functions | Static Public Member Functions | Public Attributes | Friends | List of all members
KDL::Twist Class Reference

represents both translational and rotational velocities. More...

#include <src/frames.hpp>

Collaboration diagram for KDL::Twist:
Collaboration graph
[legend]

Public Member Functions

 Twist ()
 The default constructor initialises to Zero via the constructor of Vector. More...
 
 Twist (const Vector &_vel, const Vector &_rot)
 
Twistoperator-= (const Twist &arg)
 
Twistoperator+= (const Twist &arg)
 
double & operator() (int i)
 index-based access to components, first vel(0..2), then rot(3..5) More...
 
double operator() (int i) const
 index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist More...
 
double operator[] (int index) const
 
double & operator[] (int index)
 
void ReverseSign ()
 Reverses the sign of the twist. More...
 
Twist RefPoint (const Vector &v_base_AB) const
 Changes the reference point of the twist. More...
 

Static Public Member Functions

static Twist Zero ()
 

Public Attributes

Vector vel
 The velocity of that point. More...
 
Vector rot
 The rotational velocity of that point. More...
 

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. 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...
 
bool Equal (const Twist &a, const Twist &b, double eps)
 do not use operator == because the definition of Equal(.,.) is slightly different. More...
 
bool operator== (const Twist &a, const Twist &b)
 The literal equality operator==(), also identical. More...
 
bool operator!= (const Twist &a, const Twist &b)
 The literal inequality operator!=(). More...
 

Detailed Description

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.

Constructor & Destructor Documentation

KDL::Twist::Twist ( )
inline

The default constructor initialises to Zero via the constructor of Vector.

KDL::Twist::Twist ( const Vector _vel,
const Vector _rot 
)
inline

Member Function Documentation

double & Twist::operator() ( int  i)
inline

index-based access to components, first vel(0..2), then rot(3..5)

Referenced by KDL::operator+(), and KDL::operator-().

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

Twist & Twist::operator+= ( const Twist arg)
inline
Twist & Twist::operator-= ( const Twist arg)
inline
double KDL::Twist::operator[] ( int  index) const
inline
double& KDL::Twist::operator[] ( int  index)
inline
Twist Twist::RefPoint ( const Vector v_base_AB) const
inline

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::changeRefPoint(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Segment::twist().

void Twist::ReverseSign ( )
inline

Reverses the sign of the twist.

Twist Twist::Zero ( )
inlinestatic

Friends And Related Function Documentation

double dot ( const Twist lhs,
const Wrench rhs 
)
friend
double dot ( const Wrench rhs,
const Twist lhs 
)
friend
bool Equal ( const Twist a,
const Twist b,
double  eps = epsilon 
)
friend

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
bool operator!= ( const Twist a,
const Twist b 
)
friend

The literal inequality operator!=().

Twist operator* ( const Twist lhs,
double  rhs 
)
friend
Twist operator* ( double  lhs,
const Twist rhs 
)
friend
Twist operator* ( const Twist lhs,
const Twist rhs 
)
friend

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 
)
friend

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 
)
friend
Twist operator- ( const Twist lhs,
const Twist rhs 
)
friend
Twist operator- ( const Twist arg)
friend
Twist operator/ ( const Twist lhs,
double  rhs 
)
friend
bool operator== ( const Twist a,
const Twist b 
)
friend

The literal equality operator==(), also identical.

friend class Rotation
friend
void SetToZero ( Twist v)
friend

Member Data Documentation

Vector KDL::Twist::rot
Vector KDL::Twist::vel

The documentation for this class was generated from the following files: