Other Explicit Representation for the Orientation in Robotics: Roll-Pitch-Yaw Angles
In the previous lesson, we learned about Euler Angles Representation which is one of the ways to explicitly represent an orientation. This lesson will continue with explicit ways to represent the orientation, and we will learn about Roll-Pitch-Yaw Angles.
This lesson is part of the series of lessons on foundations necessary to express robot motions. For the full comprehension of the Fundamentals of Robot Motions and the necessary tools to represent the configurations, velocities, and forces causing the motion, please read the following lessons (note that more lessons will be added in the future):
https://www.mecharithm.com/category/fundamentals-of-robotics/fundamentals-of-robot-motions/
Also, reading some lessons from the base lessons of the Fundamentals of Robotics course is beneficial.
XYZ Roll-Pitch-Yaw Angles in Robotics
In the previous lesson, we learned about Euler angles, and we saw that Euler angles refer to the angles in a sequence of rotations in a body-fixed frame. On the other hand, the roll-pitch-yaw angles are a sequence of rotations about axes of the space frame. To learn more about the body frame and the space frame, please refer to the lesson on an introduction to configurations.
Visualize Roll-Pitch-Yaw angles as a sequence of rotations relative to the space frame as the following:
According to the above figure, the body frame is initially coincident with the space frame, so it starts from the identity orientation (they have the same orientation, so the rotation matrix representing the orientation of one frame to the other is equal to identity), then following XYZ roll-pitch-yaw angles it first goes through a rotation about the space frame’s x-axis by γ followed by a rotation about the space frame’s y-axis by β and finally a rotation about the space frame’s z-axis by α. Then the final orientation can be expressed by a successive multiplication of the rotation operators as:
Note the order in which the rotation operators are written (successive rotations about the fixed frame axes). For more information, refer to the lesson on rotation matrices.
The result of the product of the three rotations is exactly the same as that for the ZYX Euler angles, but they have totally different physical interpretations. ZYX Euler angles, as we saw in the previous lesson, are a sequence of rotations relative to the body frame, whereas the XYZ Roll-Pitch-Yaw angles are a sequence of rotations relative to the fixed frame.
The terms roll, pitch, and yaw are traditionally used to describe the rotational motion of a ship or an aircraft where the roll is considered to be in the forward motion direction, the pitch is in the direction of the wing, and the yaw is towards the ground (or up):
Visualize these rotations as the following simulation
The same terminology is used in robotics. For example, in industrial robots, the end-effector’s orientation can be obtained by a combination of the roll-pitch-yaw angles. For instance, for the spherical wrist, which is very common in 6-axis industrial robots and constitutes the fourth, fifth, and sixth joints with the axes of rotation of these three joints intersect at one point (known as the wrist center), the roll-pitch-yaw angles can be defined as the following figure:
Please note that the distinguishing factor of the spherical wrist is that the three axes of rotation of the joints intersect at one point, whereas this is not the case for non-spherical wrists. For instance, in this figure, KUKA KR 210-2 has a spherical wrist since all the last three joint axes intersect at one point, but the AUBO-i5 has a non-spherical wrist since the joint axes do not intersect at a point:
Roll-pitch-yaw angles are not only used in robotic manipulators to represent the wrist’s orientation but are also used in mobile robotics:
They can also be used in aerial robotics like drones to represent the orientation of these robots:
Inverse Problem to Find a set of Roll-Pitch-Yaw Angles for a Given Orientation
Now, we want to solve the inverse problem. Suppose that we have an orientation expressed with a rotation matrix R as
and we want to find the set of Roll-Pitch-Yaw angles that can represent this orientation. Using the same approach that we used in the previous lesson, we should equate the rotation matrix obtained from the successive multiplication of the rotation operators to the given orientation expressed by the rotation matrix R:
From the first two elements of the first column, we can write:
and from the third element of the first column, we can write
If cos β ≠ 0 and thus β ≠ ±90o, then the expressions for β can be written as
Then α and γ can be found using the following equations
Now let’s solve the roll-pitch-yaw angles for a given rotation matrix when cosβ = 0 and thus β = ±90o.
- Case 1: β = π/2 then inserting the value for β in the expression for R(α,β,γ) and then equating it to the given rotation matrix, we get
From this equation, we can see that r31 = -1 and
One possible solution is when α = 0, and gamma can be calculated using one of the equations.
- Case 2: β = – π/2 then inserting the value for β in the expression for R(α,β,γ) and then equating it to the given rotation matrix, we get
From this equation, we can see that r31 = 1 and
Then one possible solution is α = 0 and γ = atan2(-r12,r22).
β = ±90o is the singularity of the XYZ Roll-Pitch-Yaw angles representation for SO(3), meaning that there are infinitely many sets of roll-pitch-yaw angles for a given rotation matrix at those angles. This is problematic in practical applications where the robot’s controller will be confused at those configurations and can generate solutions that can cause problems.
The inverse solution discussed above for the XYZ roll-pitch-yaw angles is the same as the inverse solution for the ZYX Euler angles that we discussed in the previous lesson. Although the results are the same, the two have totally different physical interpretations.
Example: Finding the Set of Roll-Pitch Yaw Angles Representing a Given Orientation Expressed by the Rotation Matrix R
Suppose the representation of an orientation is given by a rotation matrix R as
Find the equivalent sets of roll-pitch-yaw angles that can represent this orientation.
Solution:
From the first two elements of the first row, we can find the expression of cosβ as
And from the element in the third row and first column, we can see that sβ = -0.64, then
if cβ = 0.7622, then we can write
if cβ = -0.7622, then we can write
So two sets of XYZ Roll-Pitch-Yaw angles of (220.76o,-40o,38o), and (40.76o,-140o,218o) will result in the same orientation given by the rotation matrix R. This is shown in the simulation below:
Demonstration: Converting the Orientation given by roll-pitch-yaw angles to the Equivalent Euler Angles
Suppose that we have a remote controller with a known orientation given by the roll-pitch-yaw angles (γrpy,βrpy,αrpy)
In practical applications, the orientation of an object can be measured using sensors such as a gyroscope. We want to make the control system of a robotic hand follow the orientation of the remote control, but the problem is that the orientation of the robotic hand is set using ZYZ Euler angles:
We want to find a transformation that transforms the orientation of the remote control given by roll-pitch-yaw angles (γrpy,βrpy,αrpy) to the ZYZ Euler angles (αzyz,βzyz,γzyz) representation of the orientation of the robotic hand.
Solution:
The orientation of the remote control is given by roll-pitch-yaw angles (γrpy,βrpy,αrpy); therefore, the desired orientation for the robotic hand’s controller can be calculated using the rotation matrix discussed in this lesson for roll-pitch-yaw angles as
Now using the inverse solution to the ZYZ Euler angles that we developed in the previous lesson, we can find the sets of ZYZ Euler angles (the singularity-free case) for the orientation of the robotic hand given the orientation of the remote control as
or
As a numerical example, if the sensor attached to the remote control measures the orientation of the remote control approximately as the Roll-Pitch-Yaw angles of (30o,60o,45o), then in order for the robotic hand to follow this orientation, the ZYZ Euler angles using the equations above should be (11.3o,64.34o,16.10o) or (-168.69o,-64.34o,-163.89o). For your convenience, you can use the following function written in MATLAB to calculate the same result:
function [a_e,b_e,g_e] = RPY2ZYZ(a_r,b_r,g_r)
% This function converts the set of roll-pitch-yaw-angles (g_r,b_r,a_r) to the equivalent
% ZYZ Euler angles (a_e,b_e,g_e)
% it only gives the solution for the singularity-free case
% a_r, b_r, and g_r are the given roll-pitch-yaw angles in degrees
% a_r represents a rotation about the fixed z-axis
% b_r represents a rotation about the fixed y-axis
% g_r represents a rotation about the fixed x-axis
% This function is written by Dr. Madi Babaiasl
% The code is not optimized for efficiency nor robustness
% the code also does not do full error-checking on its inputs
% It is meerly for educational purposes
a_r = (a_r*pi)./180;
b_r = (b_r*pi)./180;
g_r = (g_r*pi)./180;
a_e1 = atan2((sin(a_r)*sin(b_r)*cos(g_r)-cos(a_r)*sin(g_r))./(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))),(cos(a_r)*sin(b_r)*cos(g_r)+sin(a_r)*sin(g_r))./(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))));
a_e1 = (a_e1*180)/pi;
b_e1 = atan2(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r)),cos(b_r)*cos(g_r));
b_e1 = (b_e1*180)/pi;
g_e1 = atan2((cos(b_r)*sin(g_r))./(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))),(sin(b_r))./(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))));
g_e1 = (g_e1*180)/pi;
a_e2 = atan2((sin(a_r)*sin(b_r)*cos(g_r)-cos(a_r)*sin(g_r))./-(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))),(cos(a_r)*sin(b_r)*cos(g_r)+sin(a_r)*sin(g_r))./(-sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))));
a_e2 = (a_e2*180)/pi;
b_e2 = atan2(-sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r)),cos(b_r)*cos(g_r));
b_e2 = (b_e2*180)/pi;
g_e2 = atan2((cos(b_r)*sin(g_r))./-(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))),(sin(b_r))./-(sqrt(sin(g_r)*sin(g_r)+sin(b_r)*sin(b_r)*cos(g_r)*cos(g_r))));
g_e2 = (g_e2*180)/pi;
a_e = [a_e1,a_e2];
b_e = [b_e1,b_e2];
g_e = [g_e1,g_e2];
fprintf('One set of ZYZ Euler angles are %f,%f,and %f',a_e1,b_e1,g_e1);
fprintf(',and the other set of ZYZ Euler angles are %f,%f,and %f',a_e2,b_e2,g_e2);
end
Now, let’s actually see that these sets of Euler angles will give the same orientation as the set of the roll-pitch-yaw angles representing the orientation of the remote. The demonstration below shows this.
That’s going to wrap up today’s lesson. We hope that it gave you a good understanding of roll-pitch-yaw angles and how to use them to express an orientation. We will continue with the orientation in the next lesson and see another representation to express the orientation, namely Unit Quaternions.
The video version of the current lesson can be watched at the link below:
References:
📘 Textbooks:
Modern Robotics: Mechanics, Planning, and Control by Frank Park and Kevin Lynch
A Mathematical Introduction to Robotic Manipulation by Murray, Lee, and Sastry
✍️ Logo design by Minro Art Group