Rotations in ROS
Contents
Notation
Fixed Axis vs Euler Angles
In these APIs there are two notations.
Fixed Axis For more information on fixed axis can be found here(wikipedia).
Euler Angles Euler angles are explained here(wikipedia)
C++
There are a number of math libraries including bullet and eigen and kdl. Bullet is the primary linear math library used in the system at the moment.
Bullet
There are two classes within bullet which deal with rotations, btMatrix3x3 and btQuaternion.
btMatrix3x3
Accessors
getRPY(double roll, double pitch, double yaw)
- This will get the roll pitch and yaw from the matrix about fixed axes X, Y, Z respectively.
getEulerYPR(double yaw, double pitch, double roll)
- This will get the yaw, pitch and roll from the matrix about the euler angles Z, Y, X respectively.
Mutators
setRPY(double roll, double pitch, double yaw)
- Set the rotation using fixed axis notation about X, Y, Z axes respectively.
setEulerYPR(double yaw, double pitch, double roll)
- Set the rotation using euler angles about Z, Y, X respectively.
btQuaternion
Accessors
To get angles out construct a btMatrix3x3 and use it's accessors. For example: btQuaternion q; btMatrix3x3(q).getRPY(roll, pitch, yaw);
Mutators
setRPY(double roll, double pitch, double yaw)
- Set the rotation using fixed axis notation about X, Y, Z axes respectively.
setEulerZYX
- Set the rotation using euler angles about Z, Y, X respectively.
Eigen
See Eigen's geometry tutorial.
KDL::Rotation
Constructors
Rotation::RPY(double roll, double pitch, double yaw)
- This will return a Rotation with roll pitch and yaw about fixed axes X, Y, Z respectively.
Rotation::EulerZYX(double Alfa,double Beta,double Gamma)
- Gives back a Rotation created by the EulerZYZ convention. First rotate around Z with alfa, then around the new Y with beta, then around new X with gamma.
Rotation::EulerZYZ(double Alfa,double Beta,double Gamma)
- Gives back a Rotation created by the EulerZYZ convention. First rotate around Z with alfa, then around the new Y with beta, then around new Z with gamma.
Rotation::Quaternion(double x,double y,double z, double w)
- Gives back a Rotation constructed by the 4 quaternion parameters. xyz first, and then rotation w. the norm of (x,y,z,w)) should be equal to 1.
Accessors
GetRPY(double roll, double pitch, double yaw)
- This will get the roll pitch and yaw angles about fixed axes X, Y, Z respectively.
GetEulerZYX(double alpha, double beta, double gamma)
- 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 X with gamma.
GetEulerZYZ(double alpha, double beta, double gamma)
- 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.
GetQuaternion(double x,double y,double z, double w)
- Gives back the 4 quaternion parameters. xyz first, and then rotation w. the norm of (x,y,z,w)) is equal to 1.
Python
Python euler angle support comes from transformations.py
transformations.py
The tf package also includes the popular transformations.py module. TransformerROS uses transformations.py to perform conversions between quaternions and matrices. transformations.py does has useful conversion conversion on numpy matrices; it can convert between transformations as Euler angles, quaternions, and matrices.
To use these methods, include something similar to the following line:
1 from tf.transformations import euler_from_quaternion






