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 <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
 
Twistoperator+= (const Twist &arg)
 
Twistoperator-= (const Twist &arg)
 
double operator[] (int index) const
 
double & operator[] (int index)
 
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, double rhs)
 
Twist operator* (double lhs, const Twist &rhs)
 
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, const Twist &rhs)
 
Twist operator- (const Twist &lhs, const Twist &rhs)
 
Twist operator- (const Twist &arg)
 
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)
 

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.

Definition at line 720 of file frames.hpp.

Constructor & Destructor Documentation

KDL::Twist::Twist ( )
inline

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

Definition at line 727 of file frames.hpp.

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

Definition at line 729 of file frames.hpp.

Member Function Documentation

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

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

Definition at line 327 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 336 of file frames.hpp.

Twist & KDL::Twist::operator+= ( const Twist arg)
inline

Definition at line 320 of file frames.hpp.

Twist & KDL::Twist::operator-= ( const Twist arg)
inline

Definition at line 313 of file frames.hpp.

double KDL::Twist::operator[] ( int  index) const
inline

Definition at line 740 of file frames.hpp.

double& KDL::Twist::operator[] ( int  index)
inline

Definition at line 745 of file frames.hpp.

Twist KDL::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

Definition at line 303 of file frames.hpp.

void KDL::Twist::ReverseSign ( )
inline

Reverses the sign of the twist.

Definition at line 297 of file frames.hpp.

Twist KDL::Twist::Zero ( )
inlinestatic
Returns
a zero Twist : Twist(Vector::Zero(),Vector::Zero())

Definition at line 291 of file frames.hpp.

Friends And Related Function Documentation

double dot ( const Twist lhs,
const Wrench rhs 
)
friend

Definition at line 1017 of file frames.hpp.

double dot ( const Wrench rhs,
const Twist lhs 
)
friend

Definition at line 1021 of file frames.hpp.

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

Definition at line 1050 of file frames.hpp.

friend class Frame
friend

Definition at line 790 of file frames.hpp.

bool operator!= ( const Twist a,
const Twist b 
)
friend

The literal inequality operator!=().

Definition at line 1312 of file frames.hpp.

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

Definition at line 346 of file frames.hpp.

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

Definition at line 351 of file frames.hpp.

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.

Definition at line 380 of file frames.hpp.

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.

Definition at line 384 of file frames.hpp.

Twist operator+ ( const Twist lhs,
const Twist rhs 
)
friend

Definition at line 362 of file frames.hpp.

Twist operator- ( const Twist lhs,
const Twist rhs 
)
friend

Definition at line 367 of file frames.hpp.

Twist operator- ( const Twist arg)
friend

Definition at line 373 of file frames.hpp.

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

Definition at line 356 of file frames.hpp.

bool operator== ( const Twist a,
const Twist b 
)
friend

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

Definition at line 1303 of file frames.hpp.

friend class Rotation
friend

Definition at line 789 of file frames.hpp.

void SetToZero ( Twist v)
friend

Definition at line 1072 of file frames.hpp.

Member Data Documentation

Vector KDL::Twist::rot

The rotational velocity of that point.

Definition at line 723 of file frames.hpp.

Vector KDL::Twist::vel

The velocity of that point.

Definition at line 722 of file frames.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44