Euler Angles

Since Euler angles are an intuitive way to specify a rotation in 3D, they are often exposed at user interfaces. However, there are 24 different conventions that could be used. Furthermore, you have to find out whether degrees or radians are used to express the angles (we will only use radians in pytransform3d).

Example

Here we rotate about the extrinsic (fixed) x-axis, y-axis, and z-axis by 90 degrees.

_images/plot_euler_angles.png

24 Conventions

Euler angles generally refer to three consecutive rotations about basis vectors. There are proper Euler angles for which we can distinguish 6 conventions: xzx, xyx, yxy, yzy, zyz, and zxz. As you can see, proper Euler angles rotate about the same basis vector during the first and last rotation and they rotate about another basis vector in the second rotation. In addition, there are Cardan (or Tait-Bryan) angles that rotate about three different basis vectors. There are also 6 conventions: xzy, xyz, yxz, yzx, zyx, and zxy.

If you read about Transformation Ambiguities and Conventions, you know that the order in which we concatenate rotation matrices matters. We can make extrinsic rotations, in which we rotate about basis vectors of a fixed frame, and we can make intrinsic rotations, in which we rotate about basis vectors of the new, rotated frame. This increases the amount of possible conventions to 2 (6 + 6) = 24 (if we only allow active rotation matrices).

Range of Angles

Euler angles rotate about three basis vectors with by the angles \alpha, \beta, and \gamma. If we want to find the Euler angles that correspond to one rotation matrix R, there is an infinite number of solutions because we can always add or subtract 2\pi to one of the angles and get the same result. In addition, for proper Euler angles

R(\alpha, \beta, \gamma) = R(\alpha + \pi, -\beta, \gamma - \pi).

For Cardan angles

R(\alpha, \beta, \gamma) = R(\alpha + \pi, \pi - \beta, \gamma - \pi).

For this reason the proper Euler angles are typically restricted to

-\pi \leq \alpha < \pi, \qquad 0 \leq \beta \leq \pi, \qquad -\pi \leq \gamma < \pi

and Cardan angles are usually restricted to

-\pi \leq \alpha < \pi, \qquad -\frac{\pi}{2} \leq \beta \leq \frac{\pi}{2}, \qquad -\pi \leq \gamma < \pi

to make these representations unique.

An alternative convention limits the range of \alpha and \beta to \left[0, 2 \pi\right).

Gimbal Lock

The special case of a so-called gimbal lock occurs when the second angle \beta is at one of its limits. In this case the axis of rotation for the first and last rotation are either the same or exactly opposite, that is, an infinite number of angles \alpha and \gamma will represent the same rotation even though we restricted their range to an interval of length 2\pi: either all pairs of angles that satisfy \alpha + \gamma = constant or all pairs of angles that satisfy \alpha - \gamma = constant. When we reconstruct Euler angles from a rotation matrix, we set one of these angles to 0 to determine the other.

Other Names

There are also other names for Euler angles. For example, the extrinsic xyz Cardan angles can also be called roll, pitch, and yaw (or sometimes the intrinsic convention is used here as well). Roll is a rotation about x, pitch is a rotation about y and yaw is a rotation about z.

API: Rotation Matrix / Quaternion from Euler Angles

quaternion_from_euler(e, i, j, k, extrinsic)

General conversion to quaternion from any Euler angles.

matrix_from_euler(e, i, j, k, extrinsic)

General method to compute active rotation matrix from any Euler angles.

active_matrix_from_intrinsic_euler_xzx(e)

Compute active rotation matrix from intrinsic xzx Euler angles.

active_matrix_from_extrinsic_euler_xzx(e)

Compute active rotation matrix from extrinsic xzx Euler angles.

active_matrix_from_intrinsic_euler_xyx(e)

Compute active rotation matrix from intrinsic xyx Euler angles.

active_matrix_from_extrinsic_euler_xyx(e)

Compute active rotation matrix from extrinsic xyx Euler angles.

active_matrix_from_intrinsic_euler_yxy(e)

Compute active rotation matrix from intrinsic yxy Euler angles.

active_matrix_from_extrinsic_euler_yxy(e)

Compute active rotation matrix from extrinsic yxy Euler angles.

active_matrix_from_intrinsic_euler_yzy(e)

Compute active rotation matrix from intrinsic yzy Euler angles.

active_matrix_from_extrinsic_euler_yzy(e)

Compute active rotation matrix from extrinsic yzy Euler angles.

active_matrix_from_intrinsic_euler_zyz(e)

Compute active rotation matrix from intrinsic zyz Euler angles.

active_matrix_from_extrinsic_euler_zyz(e)

Compute active rotation matrix from extrinsic zyz Euler angles.

active_matrix_from_intrinsic_euler_zxz(e)

Compute active rotation matrix from intrinsic zxz Euler angles.

active_matrix_from_extrinsic_euler_zxz(e)

Compute active rotation matrix from extrinsic zxz Euler angles.

active_matrix_from_intrinsic_euler_xzy(e)

Compute active rotation matrix from intrinsic xzy Cardan angles.

active_matrix_from_extrinsic_euler_xzy(e)

Compute active rotation matrix from extrinsic xzy Cardan angles.

active_matrix_from_intrinsic_euler_xyz(e)

Compute active rotation matrix from intrinsic xyz Cardan angles.

active_matrix_from_extrinsic_euler_xyz(e)

Compute active rotation matrix from extrinsic xyz Cardan angles.

active_matrix_from_intrinsic_euler_yxz(e)

Compute active rotation matrix from intrinsic yxz Cardan angles.

active_matrix_from_extrinsic_euler_yxz(e)

Compute active rotation matrix from extrinsic yxz Cardan angles.

active_matrix_from_intrinsic_euler_yzx(e)

Compute active rotation matrix from intrinsic yzx Cardan angles.

active_matrix_from_extrinsic_euler_yzx(e)

Compute active rotation matrix from extrinsic yzx Cardan angles.

active_matrix_from_intrinsic_euler_zyx(e)

Compute active rotation matrix from intrinsic zyx Cardan angles.

active_matrix_from_extrinsic_euler_zyx(e)

Compute active rotation matrix from extrinsic zyx Cardan angles.

active_matrix_from_intrinsic_euler_zxy(e)

Compute active rotation matrix from intrinsic zxy Cardan angles.

active_matrix_from_extrinsic_euler_zxy(e)

Compute active rotation matrix from extrinsic zxy Cardan angles.

active_matrix_from_extrinsic_roll_pitch_yaw(rpy)

Compute active rotation matrix from extrinsic roll, pitch, and yaw.

API: Euler Angles from Rotation Matrix / Quaternion

euler_from_quaternion(q, i, j, k, extrinsic)

General method to extract any Euler angles from quaternions.

euler_from_matrix(R, i, j, k, extrinsic[, ...])

General method to extract any Euler angles from active rotation matrix.

intrinsic_euler_xzx_from_active_matrix(R[, ...])

Compute intrinsic xzx Euler angles from active rotation matrix.

extrinsic_euler_xzx_from_active_matrix(R[, ...])

Compute extrinsic xzx Euler angles from active rotation matrix.

intrinsic_euler_xyx_from_active_matrix(R[, ...])

Compute intrinsic xyx Euler angles from active rotation matrix.

extrinsic_euler_xyx_from_active_matrix(R[, ...])

Compute extrinsic xyx Euler angles from active rotation matrix.

intrinsic_euler_yxy_from_active_matrix(R[, ...])

Compute intrinsic yxy Euler angles from active rotation matrix.

extrinsic_euler_yxy_from_active_matrix(R[, ...])

Compute extrinsic yxy Euler angles from active rotation matrix.

intrinsic_euler_yzy_from_active_matrix(R[, ...])

Compute intrinsic yzy Euler angles from active rotation matrix.

extrinsic_euler_yzy_from_active_matrix(R[, ...])

Compute extrinsic yzy Euler angles from active rotation matrix.

intrinsic_euler_zyz_from_active_matrix(R[, ...])

Compute intrinsic zyz Euler angles from active rotation matrix.

extrinsic_euler_zyz_from_active_matrix(R[, ...])

Compute extrinsic zyz Euler angles from active rotation matrix.

intrinsic_euler_zxz_from_active_matrix(R[, ...])

Compute intrinsic zxz Euler angles from active rotation matrix.

extrinsic_euler_zxz_from_active_matrix(R[, ...])

Compute extrinsic zxz Euler angles from active rotation matrix.

intrinsic_euler_xzy_from_active_matrix(R[, ...])

Compute intrinsic xzy Cardan angles from active rotation matrix.

extrinsic_euler_xzy_from_active_matrix(R[, ...])

Compute extrinsic xzy Cardan angles from active rotation matrix.

intrinsic_euler_xyz_from_active_matrix(R[, ...])

Compute intrinsic xyz Cardan angles from active rotation matrix.

extrinsic_euler_xyz_from_active_matrix(R[, ...])

Compute extrinsic xyz Cardan angles from active rotation matrix.

intrinsic_euler_yxz_from_active_matrix(R[, ...])

Compute intrinsic yxz Cardan angles from active rotation matrix.

extrinsic_euler_yxz_from_active_matrix(R[, ...])

Compute extrinsic yxz Cardan angles from active rotation matrix.

intrinsic_euler_yzx_from_active_matrix(R[, ...])

Compute intrinsic yzx Cardan angles from active rotation matrix.

extrinsic_euler_yzx_from_active_matrix(R[, ...])

Compute extrinsic yzx Cardan angles from active rotation matrix.

intrinsic_euler_zyx_from_active_matrix(R[, ...])

Compute intrinsic zyx Cardan angles from active rotation matrix.

extrinsic_euler_zyx_from_active_matrix(R[, ...])

Compute extrinsic zyx Cardan angles from active rotation matrix.

intrinsic_euler_zxy_from_active_matrix(R[, ...])

Compute intrinsic zxy Cardan angles from active rotation matrix.

extrinsic_euler_zxy_from_active_matrix(R[, ...])

Compute extrinsic zxy Cardan angles from active rotation matrix.

References

  1. Malcolm D. Shuster: A Survery of Attitude Representations. In: The Journal of Astronautical Sciences, Vol. 41, No.4, 1993, pp. 475-476, http://malcolmdshuster.com/Pub_1993h_J_Repsurv_scan.pdf