Working with orientation and rotation

Orientations and rotations in 3D can be represented in multiple different ways. Components which (may) have a 3D angular state, such as Body, Spherical and FreeMotion, offer the user to select the orientation representation, either Euler angles or quaternions.

Euler angles

Euler angles represent orientation using rotations around three axes, and thus uses three numbers to represent the orientation. The benefit of this representation is that it is minimal (only three numbers used), but the drawback is that any 3-number orientation representation suffers from a kinematic singularity. This representation is beneficial when you know that the singularity will not come into play in your simulation.

Most components that may use Euler angles also allow you to select the sequence of axis around which to perform the rotations, e.g., sequence = [1,2,3] performs rotations around $x$ first, then $y$ and $z$.

Quaternions

A quaternion represents an orientation using 4 numbers. This is a non-minimal representation, but in return it is also singularity free. Multibody.jl uses non-unit quaternions[quat] to represent orientation when quat = true is provided to components that support this option. The convention used for quaternions is $[s, v_1, v_2, v_3]$, sometimes also referred to as $[w, i, j, k]$, i.e., the real/scalar part comes first, followed by the three imaginary numbers. When quaternions are used, state variables denote non-unit quaternions, while normalized unit quaternions are available as observable variables Q. The use of non-unit quaternions allows Multibody to integrate rotations without using dynamic state selection or introducing algebraic equations.

Multibody.jl depends on Rotations.jl which in turn uses Quaternions.jl for quaternion computations. If you manually create quaternions using these packages, you may convert them to a vector to provide, e.g., initial conditions, using Rotations.params(Q) (see Conversion between orientation formats below).

Examples using quaternions

Rotation matrices

Rotation matrices represent orientation using a $3\times 3$ matrix $\in SO(3)$. These are used in the equations of multibody components and connectors, but should for the most part be invisible to the user. In particular, they should never appear as state variables after simplification.

Conversion between orientation formats

You may convert between different representations of orientation using the appropriate constructors from Rotations.jl, for example:

using Multibody.Rotations
using Multibody.Rotations: params
using Multibody.Rotations.Quaternions
using LinearAlgebra

R = RotMatrix{3}(I(3))
3×3 RotMatrix3{Bool} with indices SOneTo(3)×SOneTo(3):
 1  0  0
 0  1  0
 0  0  1
# Convert R to a quaternion
Q = QuatRotation(R)
3×3 QuatRotation{Float64} with indices SOneTo(3)×SOneTo(3)(QuaternionF64(1.0, 0.0, 0.0, 0.0)):
 1.0  0.0  0.0
 0.0  1.0  0.0
 0.0  0.0  1.0
# Convert Q to a 4-vector
Qvec = params(Q)
4-element StaticArraysCore.SVector{4, Float64} with indices SOneTo(4):
 1.0
 0.0
 0.0
 0.0
# Convert R to Euler angles in the sequence XYZ
E = RotXYZ(R)
3×3 RotXYZ{Float64} with indices SOneTo(3)×SOneTo(3)(0.0, 0.0, 0.0):
 1.0  -0.0   0.0
 0.0   1.0  -0.0
 0.0   0.0   1.0
# Convert E to a 3-vector
Evec = params(E)
3-element StaticArraysCore.SVector{3, Float64} with indices SOneTo(3):
 0.0
 0.0
 0.0
rotation_axis(R), rotation_angle(R) # Get an axis-angle representation
([1.0, 0.0, 0.0], 0.0)

Conventions for modeling

See Orientations and directions

Orientation API

See Orientation utilities

  • quat"Integrating Rotations using Non-Unit Quaternions", Caleb Rucker, https://par.nsf.gov/servlets/purl/10097724