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

Docstrings

    Multibody.RotationMatrixType
    RotationMatrix

    A struct representing a 3D orientation as a rotation matrix.

    If ODESystem is called on a RotationMatrix object o, symbolic variables for o.R and o.w are created and the value of o.R is used as the default value for the symbolic R.

    Fields:

    • R::R3: The rotation 3×3 matrix ∈ SO(3)
    • w: The angular velocity vector
    source
    Multibody.NumRotationMatrixMethod
    NumRotationMatrix(; R = collect(1.0 * I(3)), w = zeros(3), name, varw = false)

    Create a new RotationMatrix struct with symbolic elements. R,w determine default values.

    The primary difference between NumRotationMatrix and RotationMatrix is that the NumRotationMatrix constructor is used in the constructor of a Frame in order to introduce the frame variables, whereas RorationMatrix (the struct) only wraps existing variables.

    • varw: If true, w is a variable, otherwise it is derived from the derivative of R as w = get_w(R).

    Never call this function directly from a component constructor, instead call f = Frame(); R = ori(f) and add f to the subsystems.

    source
    Multibody.absolute_rotationMethod
    R2 = absolute_rotation(R1, Rrel)
    • R1: Orientation object to rotate frame 0 into frame 1
    • Rrel: Orientation object to rotate frame 1 into frame 2
    • R2: Orientation object to rotate frame 0 into frame 2
    source
    Multibody.axes_rotationsFunction
    axes_rotations(sequence, angles, der_angles; name = :R_ar)

    Generate a rotation matrix for a rotation around the specified axes (Euler/Cardan angles).

    source
    Multibody.axis_rotationMethod
    axis_rotation(sequence, angle; name = :R)

    Generate a rotation matrix for a rotation around the specified axis.

    • sequence: The axis to rotate around (1: x-axis, 2: y-axis, 3: z-axis)
    • angle: The angle of rotation (in radians)

    Returns a RotationMatrix object.

    source
    Multibody.connect_orientationMethod
    connect_orientation(R1,R2; iscut=false)

    Connect two rotation matrices together, optionally introducing a cut joint. A normal connection of two rotation matrices introduces 9 constraints, while a cut connection introduces 3 constraints only. This is useful to open kinematic loops, see Using cut joints (docs page) for an example where this is used.

    source
    Multibody.get_frameMethod
    T_W_F = get_frame(sol, frame, t)

    Extract a 4×4 transformation matrix ∈ SE(3) from a solution at time t.

    The transformation matrix returned, $T_W^F$, is such that when a homogenous-coordinate vector $p_F$, expressed in the local frame of reference $F$ is multiplied by $T_W^F$ as $Tp$, the resulting vector is $p_W$ expressed in the world frame:

    \[p_W = T_W^F p_F\]

    See also get_trans and get_rot, Orientations and directions (docs section).

    source
    Multibody.get_rotMethod
    R_W_F = get_rot(sol, frame, t)

    Extract a 3×3 rotation matrix ∈ SO(3) from a solution at time t.

    The rotation matrix returned, $R_W^F$, is such that when a vector $p_F$ expressed in the local frame of reference $F$ is multiplied by $R_W^F$ as $Rp$, the resulting vector is $p_W$ expressed in the world frame:

    \[p_W = R_W^F p_F\]

    This is the inverse (transpose) of the rotation matrix stored in frame connectors (e.g. ori(frame).R = get_rot(sol, frame, t)').

    The columns of $R_W_F$ indicate are the basis vectors of the frame $F$ expressed in the world coordinate frame.

    See also get_trans, get_frame, Orientations and directions (docs section).

    source
    Multibody.get_wMethod
    get_w(R)

    Compute the angular velocity w from the rotation matrix R and its derivative DR = D.(R).

    source
    Multibody.planar_rotationMethod
    planar_rotation(axis, phi, phid)

    Generate a rotation matrix for a rotation around the specified axis (axis-angle representation).

    source
    Multibody.resolve1Method
    h1 = resolve1(R21, h2)

    R12 is a 3x3 matrix that transforms a vector from frame 1 to frame 2. h2 is a vector resolved in frame 2. h1 is the same vector in frame 1.

    Typical usage (local to world):

    r_wb = resolve1(ori(frame_a), r_ab)
    source
    Multibody.resolve2Method
    h2 = resolve2(R21, h1)

    R21 is a 3x3 matrix that transforms a vector from frame 1 to frame 2. h1 is a vector resolved in frame 1. h2 is the same vector in frame 2.

    Typical usage (world to local):

    g_a = resolve2(ori(frame_a), a_0 - g_0)
    source
    • quat"Integrating Rotations using Non-Unit Quaternions", Caleb Rucker, https://par.nsf.gov/servlets/purl/10097724