math_utils module¶
Utilities module for attitude determination and control system.
This module contains a number of utility methods to simplify mathematical calculations performed elswhere. It also implements the TRIAD algorithm.
-
math_utils.
cross
(v1, v2)¶ Computes the cross product of two vectors
- NOTE: this function only exists because it outperforms numpy’s
- cross function for small vectors. Using it enables a ~2x speedup of the overall simulation
Parameters: - v1 (numpy ndarray) – an Nx1 vector
- v2 (numpy ndarray) – an Nx1 vector
Returns: the cross product of the input vectors
Return type: numpy ndarray
-
math_utils.
dcm_to_quaternion
(dcm)¶ Converts a Direction Cosine Matrix (DCM) to a quaternion
Parameters: dcm (numpy ndarray) – a 3x3 transformation matrix that parameterizes the attitude of a satellite Returns: - the equivalent right-handed quaternion (4x1) with the
- scalar part as the last entry
Return type: numpy ndarray
-
math_utils.
get_DCM_i2NED
(r)¶ Computes the inertial to NED (North-East-Down) DCM
Parameters: r (numpy ndarray) – inertial position Returns: - the 3x3 DCM representing the transformation from the
- inertial to NED frame
Return type: numpy ndarray
-
math_utils.
normalize
(vector)¶ Normalizes a vector so that its magnitude is 1
Parameters: vector (numpy ndarray) – an Nx1 vector of arbitrary magnitude Returns: the normalized vector Return type: numpy ndarray
-
math_utils.
quaternion_multiply
(q1, q2)¶ Multiplies two quaternions and returns the result
Parameters: - q1 (numpy ndarray) – a right-handed quaternion (4x1) with the scalar part as the last entry
- q2 (numpy ndarray) – a right-handed quaternion (4x1) with the scalar part as the last entry
Returns: the quaternion product of the quaternion multiplication
Return type: numpy ndarray
-
math_utils.
quaternion_to_dcm
(q)¶ Converts a quaternion to a Direction Cosine Matrix (DCM)
Parameters: q (numpy ndarray) – a right-handed quaternion (4x1) with the scalar part as the last entry Returns: - the equivalent (3x3) Direction Cosine Matrix for the
- attitude parameterized by the input quaternion
Return type: numpy ndarray
-
math_utils.
skew_symmetric
(v)¶ Returns a skew-symmetric matrix for the input vector
Parameters: v (numpy ndarray) – an Nx1 vector Returns: the skew-symmetric form of the vector (for purposes of cross-product computation) Return type: numpy ndarray
-
math_utils.
t1_matrix
(angle)¶ Returns the transformation matrix of a rotation about the 1-axis
Parameters: angle (float) – the angle of rotation about the axis (in radians) Returns: the transformation matrix for the rotation Return type: numpy ndarray
-
math_utils.
t2_matrix
(angle)¶ Returns the transformation matrix of a rotation about the 2-axis
Parameters: angle (float) – the angle of rotation about the axis (in radians) Returns: the transformation matrix for the rotation Return type: numpy ndarray
-
math_utils.
t3_matrix
(angle)¶ Returns the transformation matrix of a rotation about the 3-axis
Parameters: angle (float) – the angle of rotation about the axis (in radians) Returns: the transformation matrix for the rotation Return type: numpy ndarray
-
math_utils.
triad
(d_1_b, d_1_i, d_2_b, d_2_i)¶ Uses TRIAD to get the DCM from inertial to body
Parameters: - d_1_b (numpy ndarray) – the first (better) direction measurement in body coordinates (what your simulated sensors measure in the body frame)
- d_1_i (numpy ndarray) – the first (better) direction measurement in inertial coordinates (what your model says the direction should be)
- d_1_b – the second (worse) direction measurement in body coordinates (what your simulated sensors measure in the body frame)
- d_1_i – the second (worse) direction measurement in inertial coordinates (what your model says the direction should be)
Returns: - the 3x3 DCM representing the transformation from the
inertial to body frame
Return type: numpy ndarray