Blender  V3.3
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

 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)
 
doubleoperator() (int i)
 index-based access to components, first vel(0..2), then rot(3..5) More...
 
double operator() (int i) const
 
double operator[] (int index) const
 
doubleoperator[] (int index)
 
void ReverseSign ()
 Reverses the sign of the twist. More...
 
Twist RefPoint (const Vector &v_base_AB) const
 

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)
 
bool Equal (const Twist &a, const Twist &b, double eps)
 
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.

Definition at line 679 of file frames.hpp.

Constructor & Destructor Documentation

◆ Twist() [1/2]

KDL::Twist::Twist ( )
inline

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

Definition at line 686 of file frames.hpp.

◆ Twist() [2/2]

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

Definition at line 688 of file frames.hpp.

Member Function Documentation

◆ operator()() [1/2]

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

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

Definition at line 346 of file frames.inl.

References rot.

Referenced by operator[]().

◆ operator()() [2/2]

double 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 355 of file frames.inl.

References rot.

◆ operator+=()

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

Definition at line 339 of file frames.inl.

References rot, rot, and vel.

◆ operator-=()

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

Definition at line 332 of file frames.inl.

References rot, rot, and vel.

◆ operator[]() [1/2]

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

Definition at line 704 of file frames.hpp.

References operator()().

◆ operator[]() [2/2]

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

Definition at line 699 of file frames.hpp.

References operator()().

◆ RefPoint()

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

Definition at line 322 of file frames.inl.

References rot.

Referenced by iTaSC::ConstraintSet::closeLoop(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Segment::twist().

◆ ReverseSign()

void Twist::ReverseSign ( )
inline

Reverses the sign of the twist.

Definition at line 316 of file frames.inl.

References rot.

◆ Zero()

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

Definition at line 310 of file frames.inl.

Referenced by KDL::Joint::twist(), and iTaSC::MovingFrame::updateCoordinates().

Friends And Related Function Documentation

◆ dot [1/2]

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

◆ dot [2/2]

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

◆ Equal

bool Equal ( const Twist a,
const Twist b,
double  eps 
)
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

◆ Frame

friend class Frame
friend

Definition at line 746 of file frames.hpp.

◆ operator!=

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

The literal inequality operator!=().

◆ operator* [1/2]

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

◆ operator* [2/2]

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

◆ operator+

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

◆ operator- [1/2]

Twist operator- ( const Twist arg)
friend

◆ operator- [2/2]

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

◆ operator/

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

◆ operator==

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

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

◆ Rotation

friend class Rotation
friend

Definition at line 745 of file frames.hpp.

◆ SetToZero

void SetToZero ( Twist v)
friend

Member Data Documentation

◆ rot

Vector KDL::Twist::rot

◆ vel

Vector KDL::Twist::vel

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