archimedes.spatial.Quaternion¶
- class archimedes.spatial.Quaternion(array: ndarray)¶
Quaternion representation of a rotation in 3 dimensions.
This class is closely modeled after [scipy.spatial.transform.Rotation]( https://docs.scipy.org/doc/scipy/reference/generated/scipy.spatial.transform.Rotation.html) with a few differences:
The quaternion is always represented in scalar-first format (i.e. [w, x, y, z]) instead of scalar-last ([x, y, z, w]).
This class is designed for symbolic computation, so some checks (e.g. for valid rotation matrices) are omitted, since these cannot be done symbolically.
The class does not support multiple rotations in a single object
This implementation supports kinematic calculations
The following operations on quaternions are supported:
Application on vectors (rotations of vectors)
Quaternion Composition
Quaternion Inversion
Kinematic time derivative given angular velocity
- Parameters:
quat (array_like, shape (4,)) – Quaternion representing the rotation in scalar-first format (w, x, y, z).
- array¶
Underlying numpy array representing the quaternion.
- Type:
np.ndarray, shape (4,)
Examples
>>> from archimedes.spatial import Quaternion >>> import numpy as np
Consider a counter-clockwise rotation of 90 degrees about the z-axis. This corresponds to the following quaternion (in scalar-first format):
>>> q = Quaternion([np.cos(np.pi/4), 0, 0, np.sin(np.pi/4)])
The quaternion can be expressed in any of the other formats:
>>> q.as_matrix() array([[ 2.22044605e-16, 1.00000000e+00, 0.00000000e+00], [-1.00000000e+00, 2.22044605e-16, 0.00000000e+00], [ 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]) >>> np.rad2deg(q.as_euler('zyx')) array([90., 0., 0.])
The same quaternion can be initialized using a rotation matrix:
>>> q = Quaternion.from_matrix([[0, 1, 0], ... [-1, 0, 0], ... [0, 0, 1]])
Representation in other formats:
>>> np.rad2deg(q.as_euler('zyx')) array([90., 0., 0.])
The
from_eulermethod is flexible in the range of input formats it supports. Here we initialize a quaternion about a single axis:>>> q = Quaternion.from_euler(np.deg2rad(90), 'z')
The associated rotation matrix can be used to change coordinate systems. If the quaternion represents the orientation of a frame B relative to a frame A, then the rotation matrix transforms vectors from frame A to frame B:
>>> v_A = np.array([1, 0, 0]) # Vector in frame A >>> R_BA = q.as_matrix() >>> R_BA @ v_A # Vector in frame B [6.12323e-17, -1, 0]
The
kinematicsmethod can be used to compute the time derivative of the quaternion as an attitude representation given the angular velocity in the body frame using quaternion kinematics:>>> w_B = np.array([0, 0, np.pi/2]) # 90 deg/s about z-axis >>> q.kinematics(w_B) array([-0.55536037, 0. , 0. , 0.55536037])
See also
scipy.spatial.transform.RotationSimilar class in SciPy
RigidBodyRigid body dynamics supporting
Quaternionattitude representationeuler_to_dcmDirectly calculate rotation matrix from roll-pitch-yaw angles
euler_kinematicsTransform roll-pitch-yaw rates to body-frame angular velocity
quaternion_kinematicsLow-level quaternion kinematics function
Methods
__init__(array)as_euler(seq)Return the Euler angles from the quaternion
as_matrix()Return the quaternion as a rotation matrix.
as_quat()Return the same object - dummy method for API consistency.
from_euler(euler[, seq])Create a Quaternion from Euler angles.
from_matrix(matrix)Create a Quaternion from a rotation matrix.
from_quat(quat)Returns a copy of the Quaternion object - dummy method for API consistency.
identity()Return a quaternion representing the identity rotation.
inv()Return the inverse of the quaternion
kinematics(w[, baumgarte])Return the time derivative of the quaternion given angular velocity w.
mul(other[, normalize])Compose (multiply) this quaternion with another
normalize()Return a normalized version of this quaternion.
replace(**updates)Returns a new object replacing the specified fields with new values.
Attributes