2. SO(3): 3D Rotations#
The group of all rotations in the 3D Cartesian space is called

Overview of the representations and the conversions between them that are available in pytransform3d.#
Not all representations support all operations directly without conversion to another representation. The following table is an overview. If the operation is not implemented in pytransform3d then it is shown in brackets.
Representation |
Inverse |
Rotation of vector |
Concatenation |
Interpolation |
Renormalization |
---|---|---|---|---|---|
Rotation matrix
|
Transpose |
Yes |
Yes |
SLERP |
Required |
Axis-angle
|
Negative axis |
No |
No |
SLERP |
Not necessary |
Rotation vector
|
Negative |
No |
No |
SLERP / (2) / (3) |
Not required |
Logarithm of rotation
|
Negative |
No |
No |
SLERP / (2) / (3) |
Not required |
Quaternion
|
Conjugate |
Yes |
Yes |
SLERP |
Required |
Rotor
|
Reverse |
Yes |
Yes |
SLERP |
Required |
Euler angles
|
(1) |
No |
No |
No |
Not necessary |
Modified Rodrigues parameters
|
Negative |
No |
Yes |
No |
Not required |
Footnotes:
SLERP means Spherical Linear intERPolation. This can either be implemented directly for two instances of the representation or sometimes involves a conversion to a rotation vector that represents the difference of the two orientations.
(1) Inversion of Euler angles in convention ABC (e.g., xyz) requires using another convention CBA (e.g., zyx), reversing the order of angles, and taking the negative of these.
(2) Linear interpolation is approximately correct for small differences.
(3) Fractions of this representation represent partial rotations, but a conversion to another representation is required to interpolate between orientations.
2.1. Rotation Matrix#
One of the most practical representations of orientation is a rotation matrix
Note that this is a non-minimal representation for orientations because we
have 9 values but only 3 degrees of freedom. This is because
norm_matrix()
and checked with
matrix_requires_renormalization()
or
check_matrix()
):
column vectors must have unit norm (3 constraints)
and must be orthogonal to each other (3 constraints)
A more compact representation of these constraints is
In addition,
Hence, the group
pytransform3d uses a numpy array of shape (3, 3) to represent rotation matrices and typically we use the variable name R for a rotation matrix.
Warning
There are two conventions on how to interpret rotations: active or passive rotation. The standard in pytransform3d is an active rotation.
We can use a rotation matrix
Warning
There are two different conventions on how to use rotation matrices to apply a rotation to a vector. We can either (pre-)multiply the rotation matrix to a column vector from the left side or we can (post-)multiply it to a row vector from the right side. We will use the pre-multiplication convention.
This means that we rotate a point
This is called linear map.
Note that with our index notation (as explained in Frame Notation) and
these conventions, the second index of the rotation matrix and the left index
of the point have to be the same (
Each column of a rotation matrix
from pytransform3d.rotations import plot_basis
plot_basis()

Note
When plotting basis vectors, it is a convention to use red for the x-axis, green for the y-axis and blue for the z-axis (RGB for xyz).
We can easily chain multiple rotations: we can apply the rotation defined
by
Note that the indices have to align again. Otherwise rotations are not applied in the correct order.
Warning
There are two different conventions on how to concatenate rotation
matrices. Suppose we have a rotation matrix
The easiest way to construct rotation matrices is through rotations about the
basis vectors with active_matrix_from_angle()
.
Multiple rotation matrices that were constructed like this can be concatenated.
This will be done, for instance, to obtain rotation matrices from Euler angles
(see Euler Angles).
Pros
Supported operations: all except interpolation.
Interpretation: each column is a basis vector.
Singularities: none.
Ambiguities: none that are specific for rotation matrices.
Cons
Representation: 9 values for 3 degrees of freedom.
Renormalization: expensive in comparison to quaternions.
2.2. Axis-Angle#

Each rotation can be represented by a single rotation about one axis. The axis can be represented as a three-dimensional unit vector and the angle by a scalar:
pytransform3d uses a numpy array of shape (4,) for the axis-angle representation of a rotation, where the first 3 entries correspond to the unit axis of rotation and the fourth entry to the rotation angle in radians, and typically we use the variable name a.
Note that the axis-angle representation has a singularity at
2.3. Rotation Vector#
Since
In code, we call this the compact axis-angle representation. pytransform3d uses a numpy array of shape (3,) for the compact axis-angle representation of a rotation and typically it uses the variable name a.
We can also refer to this representation as exponential coordinates of
rotation [5]. We can represent angular velocity as
Pros
Representation: minimal.
Supported operations: interpolation; can also represent angular velocity and acceleration.
Cons
Ambiguities: an angle of 0 and any multiple of
represent the same orientation (can be avoided withnorm_compact_axis_angle()
, which introduces discontinuities); when , the axes and represent the same rotation.Supported operations: concatenation and transformation of vectors requires conversion to another representation.
2.4. Logarithm of Rotation#
In addition, we can represent cross_product_matrix()
)
where
2.5. Quaternions#
Quaternions are represented by a scalar / real part
Warning
There are two different quaternion conventions: Hamilton’s convention
defines
Read this paper for details about the two conventions and why Hamilton’s convention should be used. Section VI A gives further useful hints to identify which convention is used.
The unit quaternion space
pytransform3d uses a numpy array of shape (4,) for quaternions and typically we use the variable name q.
Warning
The scalar component
Since the other convention is also used often, pytransform3d provides the
functions quaternion_wxyz_from_xyzw()
and
quaternion_xyzw_from_wxyz()
for conversion.
Warning
The antipodal unit quaternions quaternion_double()
) represent the same
rotation (double cover). This must be considered during operations like
interpolation, distance calculation, or (approximate) equality checks.
The quaternion product
(concatenate_quaternions()
) can be used to
concatenate rotations like the matrix product can be used to concatenate
rotations represented by rotation matrices.
The inverse of the rotation represented by the unit quaternion
q_conj()
).
We can rotate a vector by representing it as a pure quaternion (i.e., with
a scalar part of 0) and then left-multiplying the quaternion and
right-multiplying its conjugate
q_prod_vector()
).
Pros
Representation: compact.
Renormalization: checked with
quaternion_requires_renormalization()
; cheap in comparison to rotation matrices (); less susceptible to round-off errors than matrix representation.Discontinuities: none.
Computational efficiency: the quaternion product is cheaper than the matrix product.
Singularities: none.
Cons
Interpretation: not straightforward.
Ambiguities: double cover.
2.6. Euler Angles#
A complete rotation can be split into three rotations around basis vectors. pytransform3d uses a numpy array of shape (3,) for Euler angles, where each entry corresponds to a rotation angle in radians around one basis vector. The basis vector that will be used and the order of rotation is defined by the convention that we use. See Euler Angles for more information.
Warning
There are 24 different conventions for defining euler angles. There are 12 different valid ways to sequence rotation axes that can be interpreted as extrinsic or intrinsic rotations: XZX, XYX, YXY, YZY, ZYZ, ZXZ, XZY, XYZ, YXZ, YZX, ZYX, and ZXY.
Pros
Representation: minimal.
Interpretation: easy to interpret for users (when the convention is clearly defined) in comparison to axis-angle or quaternions.
Cons
Ambiguities: 24 different conventions, infinitely many Euler angles represent the same rotation without proper limits for the angles.
Singularity: gimbal lock.
Supported operations: all operations require conversion to another representation.
2.7. Rotors#

Rotors and quaternions are very similar concepts in 3D. However, rotors are more general as they can be extended to more dimensions [3] [4].
The concept of a quaternion builds on the axis-angle representation, in
which we rotate by an angle about a rotation axis (see black arrow in the
illustration above). The axis can be computed from the cross product of two
vectors (gray arrows). A rotor builds on a plane-angle representation, in which
we rotate with a given direction by an angle in a plane (indicated by gray
area). The plane can be computed from the wedge product wedge()
) of two vectors
Warning
The rotors
A rotor is a unit multivector
that consists of a scalar
Warning
In pytransform3d our convention is that we organize the components of a rotor in exactly the same way as we organize the components of the equivalent quaternion. There are other conventions. It is not just possible to change the order of the scalar and the bivector (similar to a quaterion), but also to change the order of bivector components.
Pros and cons for rotors are the same as for quaternions as they have the same representation in 3D.
2.8. Modified Rodrigues Parameters#
Another minimal representation of rotation are modified Rodrigues parameters (MRP) [6] [8]
This representation is similar to the compact axis-angle representation.
However, the angle of rotation is converted to mrp_from_quaternion()
):
given some quaternion with a scalar
pytransform3d uses a numpy array of shape (3,) for modified Rodrigues parameters.
Warning
MRPs have a singuarity at mrp_near_singularity()
) which we can avoid
by ensuring the angle of rotation does not exceed norm_mrp()
).
Warning
MRPs have two representations for the same rotation:
mrp_double()
) represent
the same rotation and correspond to two antipodal unit quaternions [8].
Pros
Representation: minimal.
Cons
Interpretation: not straightforward.
Singularity: at
.Ambiguity: double cover.
Supported operations: transformation of vectors requires conversion to another representation.