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 | 
| Rotation & | operator= (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) | |
| 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... | |
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
Definition at line 301 of file frames.hpp.
| 
 | inline | 
Definition at line 306 of file frames.hpp.
| 
 | inline | 
Definition at line 499 of file frames.hpp.
Definition at line 509 of file frames.hpp.
| 
 | 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 552 of file frames.hpp.
| 
 | 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 568 of file frames.hpp.
| 
 | 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 584 of file frames.hpp.
| 
 | inlinestatic | 
EulerZYX constructs a Rotation from the Euler ZYX parameters:
Closely related to RPY-convention.
Invariants:
Definition at line 469 of file frames.hpp.
| 
 | static | 
Gives back a rotation matrix specified with EulerZYZ convention :
EulerZYX(alpha,beta,gamma) == EulerZYX(alpha +/- PHI, -beta, gamma +/- PI)
Definition at line 263 of file frames.cpp.
| 
 | 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 :
if beta == PI/2 or beta == -PI/2, multiple solutions for gamma and alpha exist. The solution where gamma==0 is chosen.
Invariants:
Closely related to RPY-convention.
Definition at line 493 of file frames.hpp.
| 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:
if beta==0 or beta==PI, then alpha and gamma are not unique, in this case gamma is chosen to be zero. Invariants:
Definition at line 276 of file frames.cpp.
| void KDL::Rotation::GetQuaternion | ( | double & | x, | 
| double & | y, | ||
| double & | z, | ||
| double & | w | ||
| ) | const | 
Get the quaternion of this matrix
Definition at line 205 of file frames.cpp.
| Vector KDL::Rotation::GetRot | ( | ) | const | 
Returns a vector with the direction of the equiv. axis and its norm is angle
Definition at line 337 of file frames.cpp.
Returns the rotation angle around the equiv. axis
| axis | the 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 the rotation angle around the equiv. axis
| axis | the 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. | 
Definition at line 359 of file frames.cpp.
| void KDL::Rotation::GetRPY | ( | double & | roll, | 
| double & | pitch, | ||
| double & | yaw | ||
| ) | const | 
Gives back a vector in RPY coordinates, variables are bound by
-PI/2 <= PITCH <= PI/2
convention :
if pitch == PI/2 or pitch == -PI/2, multiple solutions for gamma and alpha exist. The solution where roll==0 is chosen.
Invariants:
Definition at line 250 of file frames.cpp.
| 
 | inlinestatic | 
Gives back an identity rotaton matrix.
Definition at line 548 of file frames.hpp.
| 
 | inline | 
Gives back the inverse rotation matrix of *this.
Definition at line 633 of file frames.hpp.
The same as R.Inverse()*v but more efficient.
Definition at line 640 of file frames.hpp.
The same as R.Inverse()*arg but more efficient.
Definition at line 176 of file frames.hpp.
The same as R.Inverse()*arg but more efficient.
Definition at line 181 of file frames.hpp.
| 
 | inline | 
Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.
Definition at line 489 of file frames.hpp.
| 
 | inline | 
Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.
Definition at line 494 of file frames.hpp.
Defines a multiplication R*V between a Rotation R and a Vector V. Complexity : 9M+6A
Definition at line 522 of file frames.hpp.
Transformation of the base to which the twist is expressed. Complexity : 18M+12A
Definition at line 531 of file frames.hpp.
Transformation of the base to which the wrench is expressed. Complexity : 18M+12A
Definition at line 540 of file frames.hpp.
Definition at line 516 of file frames.hpp.
| 
 | 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 191 of file frames.cpp.
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 294 of file frames.cpp.
Along an arbitrary axes. rotvec should be normalized.
Definition at line 304 of file frames.cpp.
| 
 | inlinestatic | 
The Rot... static functions give the value of the appropriate rotation matrix back.
Definition at line 601 of file frames.hpp.
| 
 | inlinestatic | 
The Rot... static functions give the value of the appropriate rotation matrix back.
Definition at line 606 of file frames.hpp.
| 
 | inlinestatic | 
The Rot... static functions give the value of the appropriate rotation matrix back.
Definition at line 611 of file frames.hpp.
| 
 | 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:
Definition at line 238 of file frames.cpp.
| 
 | inline | 
Sets the value of *this to its inverse.
Definition at line 649 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 510 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 515 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 522 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 527 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 534 of file frames.hpp.
| 
 | inline | 
Access to the underlying unitvectors of the rotation matrix.
Definition at line 539 of file frames.hpp.
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 160 of file frames.cpp.
| 
 | friend | 
Definition at line 554 of file frames.hpp.
The literal inequality operator!=()
Definition at line 1321 of file frames.hpp.
Definition at line 174 of file frames.cpp.
The literal equality operator==(), also identical.
Definition at line 433 of file frames.cpp.
| double KDL::Rotation::data[9] | 
Definition at line 304 of file frames.hpp.