ADCS.controller.helpers.quaternion_math module¶
quaternion_math.py¶
Core quaternion and rotation math utilities for the ADCS framework.
This module provides quaternion algebra, rotation matrix conversions, and associated differential operations such as Jacobians and Hessians.
All functions are standalone and compatible with onboard estimator and simulator modules.
- ADCS.controller.helpers.quaternion_math.norm(v)[source]¶
Compute the Euclidean norm of a vector.
- Parameters:
v (numpy.ndarray) – Input vector.
- Returns:
n – Euclidean norm (magnitude) of the vector.
- Return type:
float
- ADCS.controller.helpers.quaternion_math.normalize(v)[source]¶
Normalize a vector to unit length.
- Parameters:
v (ndarray) – Input vector \(\mathbf{v}\).
- Returns:
Normalized vector \(\hat{\mathbf{v}} = \frac{\mathbf{v}}{\|\mathbf{v}\|}\). If \(\|\mathbf{v}\|=0\), the zero vector is returned unchanged.
- Return type:
ndarray
- ADCS.controller.helpers.quaternion_math.rot_mat(q)[source]¶
Construct the direction cosine matrix (DCM) corresponding to a quaternion using the Hamilton quaternion convention.
The returned matrix performs a rotation from the body frame to the inertial (ECI) frame, such that
\[\mathbf{v}_{\mathrm{ECI}} = \mathbf{R}(\mathbf{q})\,\mathbf{v}_{\mathrm{body}}\]where the quaternion is defined as
\[\mathbf{q} = \begin{bmatrix} q_0 & q_1 & q_2 & q_3 \end{bmatrix}^\mathsf{T}\]with scalar-first ordering.
The rotation matrix is explicitly given by
\[\begin{split}\mathbf{R}(\mathbf{q}) = \begin{bmatrix} q_0^2+q_1^2-q_2^2-q_3^2 & 2(q_1q_2-q_0q_3) & 2(q_1q_3+q_0q_2) \\ 2(q_1q_2+q_0q_3) & q_0^2-q_1^2+q_2^2-q_3^2 & 2(q_2q_3-q_0q_1) \\ 2(q_1q_3-q_0q_2) & 2(q_2q_3+q_0q_1) & q_0^2-q_1^2-q_2^2+q_3^2 \end{bmatrix}\end{split}\]- Parameters:
q (numpy.ndarray) – Unit quaternion in Hamilton form
[q0, q1, q2, q3].- Returns:
Direction cosine matrix mapping body-frame vectors to inertial frame.
- Return type:
numpy.ndarray
- ADCS.controller.helpers.quaternion_math.vector_alignment_error(q, eci_goal, body_boresight)[source]¶
Compute a minimal vector attitude error aligning a body boresight to an inertial goal.
The function returns a 3D error vector suitable for feedback control. The error represents the shortest rotation that aligns a body-fixed boresight vector with a desired inertial-frame direction.
The procedure is:
\[ \begin{align}\begin{aligned}\mathbf{v}_g^b = \mathbf{R}(q)^\top \mathbf{v}_g^{eci}\\\begin{split}\mathbf{q}_{err} = \begin{bmatrix} 1 + \mathbf{v}_g^{b\top} \mathbf{v}_b \\ \mathbf{v}_g^b \times \mathbf{v}_b \end{bmatrix}\end{split}\end{aligned}\end{align} \]followed by normalization and extraction of the vector part with shortest-rotation sign enforcement.
- Parameters:
q (numpy.ndarray) – Attitude quaternion representing the rotation from body frame to ECI frame.
eci_goal (numpy.ndarray) – Desired pointing direction expressed in the ECI frame.
body_boresight (numpy.ndarray) – Body-frame boresight direction to be aligned with the goal.
- Returns:
Vector part of the attitude error quaternion in the body frame.
- Return type:
numpy.ndarray