represents rotations in 3 dimensional space. More...
#include <src/frames.hpp>
Public Member Functions | |
| 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 & | operator= (const Rotation &arg) |
| Vector | operator* (const Vector &v) const |
| Defines a multiplication R*V between a Rotation R and a Vector V. | |
| double & | operator() (int i, int j) |
| Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set. | |
| double | operator() (int i, int j) const |
| Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set. | |
| void | SetInverse () |
| Sets the value of *this to its inverse. | |
| Rotation | Inverse () const |
| Gives back the inverse rotation matrix of *this. | |
| Vector | Inverse (const Vector &v) const |
| The same as R.Inverse()*v but more efficient. | |
| Wrench | Inverse (const Wrench &arg) const |
| The same as R.Inverse()*arg but more efficient. | |
| Twist | Inverse (const Twist &arg) const |
| The same as R.Inverse()*arg but more efficient. | |
| void | DoRotX (double angle) |
| The DoRot. | |
| void | DoRotY (double angle) |
| The DoRot. | |
| void | DoRotZ (double angle) |
| The DoRot. | |
| Vector | GetRot () const |
| Returns a vector with the direction of the equiv. | |
| double | GetRotAngle (Vector &axis, double eps=epsilon) const |
| Returns the rotation angle around the equiv. | |
| void | GetEulerZYZ (double &alfa, double &beta, double &gamma) const |
| Gives back the EulerZYZ convention description of the rotation matrix : First rotate around Z with alfa, then around the new Y with beta, then around new Z with gamma. | |
| void | GetQuaternion (double &x, double &y, double &z, double &w) const |
| Get the quaternion of this matrix. | |
| void | 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. | |
| void | GetEulerZYX (double &Alfa, double &Beta, double &Gamma) const |
| 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. | |
| Twist | operator* (const Twist &arg) const |
| Transformation of the base to which the twist is expressed. | |
| Wrench | operator* (const Wrench &arg) const |
| Transformation of the base to which the wrench is expressed. | |
| Vector | UnitX () const |
| Access to the underlying unitvectors of the rotation matrix. | |
| void | UnitX (const Vector &X) |
| Access to the underlying unitvectors of the rotation matrix. | |
| Vector | UnitY () const |
| Access to the underlying unitvectors of the rotation matrix. | |
| void | UnitY (const Vector &X) |
| Access to the underlying unitvectors of the rotation matrix. | |
| Vector | UnitZ () const |
| Access to the underlying unitvectors of the rotation matrix. | |
| void | UnitZ (const Vector &X) |
| Access to the underlying unitvectors of the rotation matrix. | |
Static Public Member Functions | |
| static Rotation | Identity () |
| Gives back an identity rotaton matrix. | |
| static Rotation | RotX (double angle) |
| The Rot... static functions give the value of the appropriate rotation matrix back. | |
| static Rotation | RotY (double angle) |
| The Rot... static functions give the value of the appropriate rotation matrix back. | |
| static Rotation | RotZ (double angle) |
| The Rot... static functions give the value of the appropriate rotation matrix back. | |
| static Rotation | Rot (const Vector &rotvec, double angle) |
| Along an arbitrary axes. | |
| static Rotation | Rot2 (const Vector &rotvec, double angle) |
| Along an arbitrary axes. rotvec should be normalized. | |
| static Rotation | EulerZYZ (double Alfa, double Beta, double Gamma) |
| 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. | |
| static Rotation | Quaternion (double x, double y, double z, double w) |
| Sets the value of this object to a rotation specified with Quaternion convention the norm of (x,y,z,w) should be equal to 1. | |
| static Rotation | RPY (double roll, double pitch, double yaw) |
| Sets the value of this object to a rotation specified with RPY convention: first rotate around X with roll, then around the old Y with pitch, then around old Z with alfa. | |
| static Rotation | EulerZYX (double Alfa, double Beta, double Gamma) |
| Gives back a rotation matrix specified with EulerZYX convention : First rotate around Z with alfa, then around the new Y with beta, then around new X with gamma. | |
Public Attributes | |
| double | data [9] |
Friends | |
| class | Frame |
| Rotation | operator* (const Rotation &lhs, const Rotation &rhs) |
| bool | Equal (const Rotation &a, const Rotation &b, double eps=epsilon) |
| do not use operator == because the definition of Equal(.,. | |
| bool | operator== (const Rotation &a, const Rotation &b) |
| The literal equality operator==(), also identical. | |
| bool | operator!= (const Rotation &a, const Rotation &b) |
| The literal inequality operator!=(). | |
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 collumns [ 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
| KDL::Rotation::Rotation | ( | ) | [inline] |
References Identity().
Referenced by RPY().
| KDL::Rotation::Rotation | ( | double | Xx, | |
| double | Yx, | |||
| double | Zx, | |||
| double | Xy, | |||
| double | Yy, | |||
| double | Zy, | |||
| double | Xz, | |||
| double | Yz, | |||
| double | Zz | |||
| ) | [inline] |
| void KDL::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
| void KDL::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
| void KDL::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
| static Rotation KDL::Rotation::EulerZYX | ( | double | Alfa, | |
| double | Beta, | |||
| double | Gamma | |||
| ) | [inline, static] |
Gives back a rotation matrix specified with EulerZYX convention : First rotate around Z with alfa, then around the new Y with beta, then around new X with gamma.
closely related to RPY-convention
References RPY().
| 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.
| 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
Closely related to RPY-convention.
References GetRPY().
| void KDL::Rotation::GetEulerZYZ | ( | double & | alfa, | |
| double & | beta, | |||
| double & | gamma | |||
| ) | const |
Gives back the EulerZYZ convention description of the rotation matrix : First rotate around Z with alfa, then around the new Y with beta, then around new Z with gamma.
Variables are bound by (-PI <= alfa <= PI), (0 <= beta <= PI), (-PI <= alfa <= PI)
References data.
| void KDL::Rotation::GetQuaternion | ( | double & | x, | |
| double & | y, | |||
| double & | z, | |||
| double & | w | |||
| ) | const |
Get the quaternion of this matrix.
| Vector KDL::Rotation::GetRot | ( | ) | const |
Returns a vector with the direction of the equiv.
axis and its norm is angle
| double KDL::Rotation::GetRotAngle | ( | Vector & | axis, | |
| double | eps = epsilon | |||
| ) | const |
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 choosen to be +/- Z-axis in the case of angle == PI : 2 solutions, positive Z-component of the axis is choosen. |
axis
| axis | the rotation axis is returned in this variable | |
| eps | : in the case of angle == 0 : rot axis is undefined and choosen to be +/- Z-axis in the case of angle == PI : 2 solutions, positive Z-component of the axis is choosen. |
Referenced by KDL::RotationalInterpolation_SingleAxis::SetStartEnd().
| 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 alfa
Referenced by GetEulerZYX(), and KDL::KDLToolkitPlugin::loadConstructors().
| Rotation KDL::Rotation::Identity | ( | ) | [inline, static] |
Gives back an identity rotaton matrix.
Referenced by Rotation().
The same as R.Inverse()*arg but more efficient.
The same as R.Inverse()*arg but more efficient.
The same as R.Inverse()*v but more efficient.
| Rotation KDL::Rotation::Inverse | ( | ) | const [inline] |
Gives back the inverse rotation matrix of *this.
Referenced by KDL::RotationalInterpolation_SingleAxis::SetStartEnd().
| double KDL::Rotation::operator() | ( | int | i, | |
| int | j | |||
| ) | const [inline] |
Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.
| double & KDL::Rotation::operator() | ( | int | i, | |
| int | j | |||
| ) | [inline] |
Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set.
Transformation of the base to which the wrench is expressed.
Complexity : 18M+12A
Transformation of the base to which the twist is expressed.
Complexity : 18M+12A
| Rotation KDL::Rotation::Quaternion | ( | double | x, | |
| double | y, | |||
| double | z, | |||
| double | w | |||
| ) | [static] |
Sets the value of this object to a rotation specified with Quaternion convention the norm of (x,y,z,w) should be equal to 1.
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.
Referenced by KDL::Path_Line::Path_Line().
Along an arbitrary axes. rotvec should be normalized.
Referenced by KDL::Joint::Joint(), KDL::RotationalInterpolation_SingleAxis::Pos(), and KDL::Joint::pose().
| Rotation KDL::Rotation::RotX | ( | double | angle | ) | [inline, static] |
The Rot... static functions give the value of the appropriate rotation matrix back.
Referenced by KDL::Joint::pose().
| Rotation KDL::Rotation::RotY | ( | double | angle | ) | [inline, static] |
The Rot... static functions give the value of the appropriate rotation matrix back.
Referenced by KDL::Joint::pose().
| Rotation KDL::Rotation::RotZ | ( | double | angle | ) | [inline, static] |
The Rot... static functions give the value of the appropriate rotation matrix back.
Referenced by KDL::Joint::pose().
| Rotation KDL::Rotation::RPY | ( | double | roll, | |
| double | pitch, | |||
| double | yaw | |||
| ) | [static] |
Sets the value of this object to a rotation specified with RPY convention: first rotate around X with roll, then around the old Y with pitch, then around old Z with alfa.
References Rotation().
Referenced by EulerZYX().
| void KDL::Rotation::SetInverse | ( | ) | [inline] |
Sets the value of *this to its inverse.
| void KDL::Rotation::UnitX | ( | const Vector & | X | ) | [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
| Vector KDL::Rotation::UnitX | ( | ) | const [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
| void KDL::Rotation::UnitY | ( | const Vector & | X | ) | [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
| Vector KDL::Rotation::UnitY | ( | ) | const [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
Referenced by KDL::Path_Circle::Clone(), and KDL::Path_Circle::Write().
| void KDL::Rotation::UnitZ | ( | const Vector & | X | ) | [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
| Vector KDL::Rotation::UnitZ | ( | ) | const [inline] |
Access to the underlying unitvectors of the rotation matrix.
References data.
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] |
The literal inequality operator!=().
The literal equality operator==(), also identical.
| double KDL::Rotation::data[9] |
Referenced by KDL::Equal(), GetEulerZYZ(), KDL::Frame::operator*(), KDL::operator*(), KDL::operator+(), UnitX(), UnitY(), and UnitZ().
1.6.3