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

represents rotations in 3 dimensional space. More...

#include <frames.hpp>

Public Member Functions

void DoRotX (double angle)
 
void DoRotY (double angle)
 
void DoRotZ (double angle)
 
void GetEulerZYX (double &Alfa, double &Beta, double &Gamma) const
 
void GetEulerZYZ (double &alpha, double &beta, double &gamma) const
 
void GetQuaternion (double &x, double &y, double &z, double &w) const
 
Vector GetRot () const
 
double GetRotAngle (Vector &axis, double eps=epsilon) const
 
void GetRPY (double &roll, double &pitch, double &yaw) const
 
Rotation Inverse () const
 Gives back the inverse rotation matrix of *this. More...
 
Vector Inverse (const Vector &v) const
 The same as R.Inverse()*v but more efficient. More...
 
Wrench Inverse (const Wrench &arg) const
 The same as R.Inverse()*arg but more efficient. More...
 
Twist Inverse (const Twist &arg) const
 The same as R.Inverse()*arg but more efficient. More...
 
double & operator() (int i, int j)
 Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set. More...
 
double operator() (int i, int j) const
 Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set. More...
 
Vector operator* (const Vector &v) const
 
Twist operator* (const Twist &arg) const
 
Wrench operator* (const Wrench &arg) const
 
Rotationoperator= (const Rotation &arg)
 
 Rotation ()
 
 Rotation (double Xx, double Yx, double Zx, double Xy, double Yy, double Zy, double Xz, double Yz, double Zz)
 
 Rotation (const Vector &x, const Vector &y, const Vector &z)
 
 Rotation (const Rotation &arg)
 
void SetInverse ()
 Sets the value of *this to its inverse. More...
 
Vector UnitX () const
 Access to the underlying unitvectors of the rotation matrix. More...
 
void UnitX (const Vector &X)
 Access to the underlying unitvectors of the rotation matrix. More...
 
Vector UnitY () const
 Access to the underlying unitvectors of the rotation matrix. More...
 
void UnitY (const Vector &X)
 Access to the underlying unitvectors of the rotation matrix. More...
 
Vector UnitZ () const
 Access to the underlying unitvectors of the rotation matrix. More...
 
void UnitZ (const Vector &X)
 Access to the underlying unitvectors of the rotation matrix. More...
 

Static Public Member Functions

static Rotation EulerZYX (double Alfa, double Beta, double Gamma)
 
static Rotation EulerZYZ (double Alfa, double Beta, double Gamma)
 
static Rotation Identity ()
 Gives back an identity rotaton matrix. More...
 
static Rotation Quaternion (double x, double y, double z, double w)
 
static Rotation Rot (const Vector &rotvec, double angle)
 
static Rotation Rot2 (const Vector &rotvec, double angle)
 Along an arbitrary axes. rotvec should be normalized. More...
 
static Rotation RotX (double angle)
 The Rot... static functions give the value of the appropriate rotation matrix back. More...
 
static Rotation RotY (double angle)
 The Rot... static functions give the value of the appropriate rotation matrix back. More...
 
static Rotation RotZ (double angle)
 The Rot... static functions give the value of the appropriate rotation matrix back. More...
 
static Rotation RPY (double roll, double pitch, double yaw)
 

Public Attributes

double data [9]
 

Friends

bool Equal (const Rotation &a, const Rotation &b, double eps)
 
class Frame
 
bool operator!= (const Rotation &a, const Rotation &b)
 The literal inequality operator!=() More...
 
Rotation operator* (const Rotation &lhs, const Rotation &rhs)
 
bool operator== (const Rotation &a, const Rotation &b)
 The literal equality operator==(), also identical. More...
 

Detailed Description

represents rotations in 3 dimensional space.

This class represents a rotation matrix with the following conventions :

    Suppose V2 = R*V,                                    (1)
    V is expressed in frame B
    V2 is expressed in frame A
    This matrix R consists of 3 columns [ X,Y,Z ],
    X,Y, and Z contain the axes of frame B, expressed in frame A
    Because of linearity expr(1) is valid.

This class only represents rotational_interpolation, not translation Two interpretations are possible for rotation angles. if you rotate with angle around X frame A to have frame B, then the result of SetRotX is equal to frame B expressed wrt A. In code:

     Rotation R;
     F_A_B = R.SetRotX(angle);

Secondly, if you take the following code :

     Vector p,p2; Rotation R;
     R.SetRotX(angle);
     p2 = R*p;

then the frame p2 is rotated around X axis with (-angle). Analogue reasonings can be applyd to SetRotY,SetRotZ,SetRot

type
Concrete implementation

Definition at line 303 of file frames.hpp.

Constructor & Destructor Documentation

◆ Rotation() [1/4]

KDL::Rotation::Rotation ( )
inline

Definition at line 308 of file frames.hpp.

◆ Rotation() [2/4]

Rotation::Rotation ( double  Xx,
double  Yx,
double  Zx,
double  Xy,
double  Yy,
double  Zy,
double  Xz,
double  Yz,
double  Zz 
)
inline

Definition at line 499 of file frames.hpp.

◆ Rotation() [3/4]

Rotation::Rotation ( const Vector x,
const Vector y,
const Vector z 
)
inline

Definition at line 509 of file frames.hpp.

◆ Rotation() [4/4]

Rotation::Rotation ( const Rotation arg)
inline

Definition at line 516 of file frames.hpp.

Member Function Documentation

◆ DoRotX()

void Rotation::DoRotX ( double  angle)
inline

The DoRot... functions apply a rotation R to *this,such that *this = *this * Rot.. DoRot... functions are only defined when they can be executed more efficiently

Definition at line 557 of file frames.hpp.

◆ DoRotY()

void Rotation::DoRotY ( double  angle)
inline

The DoRot... functions apply a rotation R to *this,such that *this = *this * Rot.. DoRot... functions are only defined when they can be executed more efficiently

Definition at line 573 of file frames.hpp.

◆ DoRotZ()

void Rotation::DoRotZ ( double  angle)
inline

The DoRot... functions apply a rotation R to *this,such that *this = *this * Rot.. DoRot... functions are only defined when they can be executed more efficiently

Definition at line 589 of file frames.hpp.

◆ EulerZYX()

static Rotation KDL::Rotation::EulerZYX ( double  Alfa,
double  Beta,
double  Gamma 
)
inlinestatic

EulerZYX constructs a Rotation from the Euler ZYX parameters:

  • First rotate around Z with alfa,
  • then around the new Y with beta,
  • then around new X with gamma.

Closely related to RPY-convention.

Invariants:

  • EulerZYX(alpha,beta,gamma) == EulerZYX(alpha +/- PI, PI-beta, gamma +/- PI)
  • (angle + 2*k*PI)

Definition at line 471 of file frames.hpp.

◆ EulerZYZ()

Rotation KDL::Rotation::EulerZYZ ( double  Alfa,
double  Beta,
double  Gamma 
)
static

Gives back a rotation matrix specified with EulerZYZ convention :

  • First rotate around Z with alfa,
  • then around the new Y with beta,
  • then around new Z with gamma. Invariants:

EulerZYX(alpha,beta,gamma) == EulerZYX(alpha +/- PHI, -beta, gamma +/- PI)

  • (angle + 2*k*PI)

Definition at line 262 of file frames.cpp.

◆ GetEulerZYX()

void KDL::Rotation::GetEulerZYX ( double &  Alfa,
double &  Beta,
double &  Gamma 
) const
inline

GetEulerZYX gets the euler ZYX parameters of a rotation : First rotate around Z with alfa, then around the new Y with beta, then around new X with gamma.

Range of the results of GetEulerZYX :

  • -PI <= alfa <= PI
  • -PI <= gamma <= PI
  • -PI/2 <= beta <= PI/2

if beta == PI/2 or beta == -PI/2, multiple solutions for gamma and alpha exist. The solution where gamma==0 is chosen.

Invariants:

  • EulerZYX(alpha,beta,gamma) == EulerZYX(alpha +/- PI, PI-beta, gamma +/- PI)
  • and also (angle + 2*k*PI)

Closely related to RPY-convention.

Definition at line 495 of file frames.hpp.

◆ GetEulerZYZ()

void KDL::Rotation::GetEulerZYZ ( double &  alpha,
double &  beta,
double &  gamma 
) const

Gives back the EulerZYZ convention description of the rotation matrix : First rotate around Z with alpha, then around the new Y with beta, then around new Z with gamma.

Variables are bound by:

  • (-PI < alpha <= PI),
  • (0 <= beta <= PI),
  • (-PI < gamma <= PI)

if beta==0 or beta==PI, then alpha and gamma are not unique, in this case gamma is chosen to be zero. Invariants:

  • EulerZYX(alpha,beta,gamma) == EulerZYX(alpha +/- PI, -beta, gamma +/- PI)
  • angle + 2*k*PI

Definition at line 275 of file frames.cpp.

◆ GetQuaternion()

void KDL::Rotation::GetQuaternion ( double &  x,
double &  y,
double &  z,
double &  w 
) const

Get the quaternion of this matrix

Postcondition
the norm of (x,y,z,w) is 1

Definition at line 204 of file frames.cpp.

◆ GetRot()

Vector KDL::Rotation::GetRot ( ) const

Returns a vector with the direction of the equiv. axis and its norm is angle

Definition at line 336 of file frames.cpp.

◆ GetRotAngle()

double KDL::Rotation::GetRotAngle ( Vector axis,
double  eps = epsilon 
) const

Returns the rotation angle around the equiv. axis

Parameters
axisthe rotation axis is returned in this variable
eps: in the case of angle == 0 : rot axis is undefined and chosen to be +/- Z-axis in the case of angle == PI : 2 solutions, positive Z-component of the axis is chosen.
Returns
returns the rotation angle (between [0..PI] )

Returns the rotation angle around the equiv. axis

Parameters
axisthe rotation axis is returned in this variable
eps: in the case of angle == 0 : rot axis is undefined and chosen to be the Z-axis in the case of angle == PI : 2 solutions, positive Z-component of the axis is chosen.
Returns
returns the rotation angle (between [0..PI] ) /todo : Check corresponding routines in rframes and rrframes

Definition at line 358 of file frames.cpp.

◆ GetRPY()

void KDL::Rotation::GetRPY ( double &  roll,
double &  pitch,
double &  yaw 
) const

Gives back a vector in RPY coordinates, variables are bound by

  • -PI <= roll <= PI
  • -PI <= Yaw <= PI
  • -PI/2 <= PITCH <= PI/2

convention :

  • first rotate around X with roll,
  • then around the old Y with pitch,
  • then around old Z with yaw

if pitch == PI/2 or pitch == -PI/2, multiple solutions for gamma and alpha exist. The solution where roll==0 is chosen.

Invariants:

  • RPY(roll,pitch,yaw) == RPY( roll +/- PI, PI-pitch, yaw +/- PI )
  • angles + 2*k*PI

Definition at line 249 of file frames.cpp.

◆ Identity()

Rotation Rotation::Identity ( )
inlinestatic

Gives back an identity rotaton matrix.

Definition at line 553 of file frames.hpp.

◆ Inverse() [1/4]

Rotation Rotation::Inverse ( ) const
inline

Gives back the inverse rotation matrix of *this.

Definition at line 638 of file frames.hpp.

◆ Inverse() [2/4]

Vector Rotation::Inverse ( const Vector v) const
inline

The same as R.Inverse()*v but more efficient.

Definition at line 645 of file frames.hpp.

◆ Inverse() [3/4]

Wrench Rotation::Inverse ( const Wrench arg) const
inline

The same as R.Inverse()*arg but more efficient.

Definition at line 176 of file frames.hpp.

◆ Inverse() [4/4]

Twist Rotation::Inverse ( const Twist arg) const
inline

The same as R.Inverse()*arg but more efficient.

Definition at line 181 of file frames.hpp.

◆ operator()() [1/2]

double & Rotation::operator() ( int  i,
int  j 
)
inline

Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.

Definition at line 489 of file frames.hpp.

◆ operator()() [2/2]

double Rotation::operator() ( int  i,
int  j 
) const
inline

Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.

Definition at line 494 of file frames.hpp.

◆ operator*() [1/3]

Vector Rotation::operator* ( const Vector v) const
inline

Defines a multiplication R*V between a Rotation R and a Vector V. Complexity : 9M+6A

Definition at line 527 of file frames.hpp.

◆ operator*() [2/3]

Twist Rotation::operator* ( const Twist arg) const
inline

Transformation of the base to which the twist is expressed. Complexity : 18M+12A

See also
Frame*Twist for a transformation that also transforms the velocity reference point.

Definition at line 536 of file frames.hpp.

◆ operator*() [3/3]

Wrench Rotation::operator* ( const Wrench arg) const
inline

Transformation of the base to which the wrench is expressed. Complexity : 18M+12A

See also
Frame*Wrench for a transformation that also transforms the force reference point.

Definition at line 545 of file frames.hpp.

◆ operator=()

Rotation & Rotation::operator= ( const Rotation arg)
inline

Definition at line 521 of file frames.hpp.

◆ Quaternion()

Rotation KDL::Rotation::Quaternion ( double  x,
double  y,
double  z,
double  w 
)
static

Gives back a rotation matrix specified with Quaternion convention the norm of (x,y,z,w) should be equal to 1

Definition at line 190 of file frames.cpp.

◆ Rot()

Rotation KDL::Rotation::Rot ( const Vector rotvec,
double  angle 
)
static

Along an arbitrary axes. It is not necessary to normalize rotvec. returns identity rotation matrix in the case that the norm of rotvec is to small to be used.

Definition at line 293 of file frames.cpp.

◆ Rot2()

Rotation KDL::Rotation::Rot2 ( const Vector rotvec,
double  angle 
)
static

Along an arbitrary axes. rotvec should be normalized.

Definition at line 303 of file frames.cpp.

◆ RotX()

Rotation Rotation::RotX ( double  angle)
inlinestatic

The Rot... static functions give the value of the appropriate rotation matrix back.

Definition at line 606 of file frames.hpp.

◆ RotY()

Rotation Rotation::RotY ( double  angle)
inlinestatic

The Rot... static functions give the value of the appropriate rotation matrix back.

Definition at line 611 of file frames.hpp.

◆ RotZ()

Rotation Rotation::RotZ ( double  angle)
inlinestatic

The Rot... static functions give the value of the appropriate rotation matrix back.

Definition at line 616 of file frames.hpp.

◆ RPY()

Rotation KDL::Rotation::RPY ( double  roll,
double  pitch,
double  yaw 
)
static

Gives back a rotation matrix specified with RPY convention: first rotate around X with roll, then around the old Y with pitch, then around old Z with yaw

Invariants:

  • RPY(roll,pitch,yaw) == RPY( roll +/- PI, PI-pitch, yaw +/- PI )
  • angles + 2*k*PI

Definition at line 237 of file frames.cpp.

◆ SetInverse()

void Rotation::SetInverse ( )
inline

Sets the value of *this to its inverse.

Definition at line 654 of file frames.hpp.

◆ UnitX() [1/2]

Vector KDL::Rotation::UnitX ( ) const
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 512 of file frames.hpp.

◆ UnitX() [2/2]

void KDL::Rotation::UnitX ( const Vector X)
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 517 of file frames.hpp.

◆ UnitY() [1/2]

Vector KDL::Rotation::UnitY ( ) const
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 524 of file frames.hpp.

◆ UnitY() [2/2]

void KDL::Rotation::UnitY ( const Vector X)
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 529 of file frames.hpp.

◆ UnitZ() [1/2]

Vector KDL::Rotation::UnitZ ( ) const
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 536 of file frames.hpp.

◆ UnitZ() [2/2]

void KDL::Rotation::UnitZ ( const Vector X)
inline

Access to the underlying unitvectors of the rotation matrix.

Definition at line 541 of file frames.hpp.

Friends And Related Function Documentation

◆ Equal

bool Equal ( const Rotation a,
const Rotation 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

Definition at line 159 of file frames.cpp.

◆ Frame

friend class Frame
friend

Definition at line 556 of file frames.hpp.

◆ operator!=

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

The literal inequality operator!=()

Definition at line 1328 of file frames.hpp.

◆ operator*

Rotation operator* ( const Rotation lhs,
const Rotation rhs 
)
friend

Definition at line 173 of file frames.cpp.

◆ operator==

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

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

Definition at line 430 of file frames.cpp.

Member Data Documentation

◆ data

double KDL::Rotation::data[9]

Definition at line 306 of file frames.hpp.


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


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:15