ADCS.estimators.attitude_estimators.attitude_estimator module¶
- class ADCS.estimators.attitude_estimators.attitude_estimator.Attitude_Estimator(est_sat, J2000, x_hat, P_hat, Q_hat, dt=1, cross_term=False, quat_as_vec=False)[source]¶
Bases:
objectAbstract base class for spacecraft attitude and bias estimators.
This base class provides shared bookkeeping and interfaces for estimators operating on an
EstimatedSatellitemodel, including:storage of the full augmented state vector,
storage of covariance and process-noise matrices in a reduced attitude space (3-DOF attitude error instead of a 4-parameter quaternion),
synchronization of the internal satellite model via
match_estimate().
Augmented state definition¶
The estimator maintains an augmented state of the form
\[\begin{split}\mathbf{x} = \begin{bmatrix} \boldsymbol{\omega} \\ \mathbf{q} \\ \mathbf{h}_{RW} \\ \mathbf{b}_{act} \\ \mathbf{b}_{sens} \\ \boldsymbol{\theta}_{dist} \end{bmatrix} \in \mathbb{R}^{N},\end{split}\]where:
\[\boldsymbol{\omega} \in \mathbb{R}^3,\quad \mathbf{q} \in \mathbb{R}^4,\quad \mathbf{h}_{RW} \in \mathbb{R}^{n_{RW}},\quad \mathbf{b}_{act} \in \mathbb{R}^{n_{ab}},\quad \mathbf{b}_{sens} \in \mathbb{R}^{n_{sb}},\quad \boldsymbol{\theta}_{dist} \in \mathbb{R}^{n_{dp}}.\]Hence the total augmented dimension is
\[N = 7 + n_{RW} + n_{ab} + n_{sb} + n_{dp}.\]Reduced covariance representation¶
The state contains a quaternion \(\mathbf{q}\in\mathbb{R}^4\), but the covariance is typically stored in a minimal 3-DOF attitude-error space to avoid the unit-norm constraint in the covariance representation. Thus, the covariance and process noise live in
\[\mathbb{R}^{(N-1)\times(N-1)}\]where one quaternion component is dropped and replaced by a 3-parameter attitude error (e.g., error-angle vector). Subclasses (e.g., MEKF, SRUKF) define the mapping between the full state and this reduced covariance space.
If
quat_as_vec=True, then the covariance and process noise are stored in the full space (no reduction), i.e. shape \(N\times N\).References
Satellite model synchronization is performed with
match_estimate().Reduced covariance sub-selection is performed with
square_mat_sections().
- cov_use()[source]¶
Return a boolean mask for the reduced covariance state.
The attribute
useis a boolean mask over the full augmented state \(\mathbf{x}\in\mathbb{R}^{N}\). The covariance is stored in a reduced attitude-error space of dimension \(N-1\), where the quaternion is represented minimally.This method converts the full-state mask into a reduced-state mask by deleting the entry corresponding to the dropped quaternion component (index 3 in the full state vector ordering).
Quaternion reduction convention¶
If the full state begins as
\[\begin{split}\mathbf{x} = \begin{bmatrix} \omega_x \\ \omega_y \\ \omega_z \\ q_0 \\ q_1 \\ q_2 \\ q_3 \\ \vdots \end{bmatrix},\end{split}\]then index 3 corresponds to the first quaternion component in the full storage convention and is removed to obtain a mask compatible with the reduced covariance representation.
- param:
None.
- type:
None
- return:
Boolean mask of length \(N-1\) compatible with the reduced covariance matrices.
- rtype:
numpy.ndarray
- Return type:
ndarray
- initialize_estimate(gyro_readings, mtm_readings, sunpair_readings, sunsensor_readings, B_ECI, S_ECI, os, q=None)[source]¶
Robust initial attitude and bias estimation.
This routine builds an initial attitude quaternion (and optionally a gyro bias / angular rate guess) from a subset of available sensor measurements. Any measurement may be omitted by passing
None.Attitude initialization via Wahba’s problem¶
If an initial quaternion
qis not provided, this method estimates it by solving Wahba’s problem using all available vector observations.Given body-frame measurements \(\mathbf{v}_{b,i}\) and their inertial references \(\mathbf{v}_{I,i}\), we seek the rotation \(\mathbf{R}\) (or quaternion \(\mathbf{q}\)) minimizing
\[J(\mathbf{R}) = \sum_{i=1}^{m} w_i \left\lVert \mathbf{v}_{b,i} - \mathbf{R}\,\mathbf{v}_{I,i} \right\rVert^2,\]with weights \(w_i>0\). The solution is computed using
wahbas_svd().Measurement weighting¶
Each available vector observation is weighted by an inverse-variance-like term combining sensor noise and current prior bias uncertainty:
\[w_i = \frac{1}{\sigma_i^2 + P_{\text{bias},i}},\]where \(\sigma_i^2\) is the sensor noise variance and \(P_{\text{bias},i}\) is the corresponding scalar bias variance extracted from the current covariance
x_hat.covat the sensor’s bias index.Sensors used (when available) are:
Magnetometer (body) with reference \(\mathbf{B}_{ECI}\),
Sun sensor (body) with reference \(\mathbf{S}_{ECI}\),
Sun sensor pair (body) with reference \(\mathbf{S}_{ECI}\).
Gyro bias and angular-rate guess (optional)¶
If a gyroscope reading \(\tilde{\boldsymbol{\omega}}\) is available, the method forms a simple linear estimator using:
gyro bias covariance block \(P_b\),
gyro measurement noise \(R_g\),
rate covariance \(Q_\omega\).
A typical structure consistent with the implementation is
\[\hat{\mathbf{b}}_g = (R_g + P_b + Q_\omega)^{-1} P_b \,\tilde{\boldsymbol{\omega}}.\]The method then constructs an approximate rate guess \(\hat{\boldsymbol{\omega}}\) from the bias and covariance blocks.
Satellite synchronization¶
The updated augmented state is committed into
x_hat.valand then pushed to the internal satellite model viamatch_estimate().- param gyro_readings:
Gyroscope measurement in the body frame, shape
(3,). IfNone, gyro bias and rate are not updated.- type gyro_readings:
numpy.ndarray or None
- param mtm_readings:
Magnetometer measurement in the body frame, shape
(3,).- type mtm_readings:
numpy.ndarray or None
- param sunpair_readings:
Sun sensor pair measurement in the body frame, shape
(3,).- type sunpair_readings:
numpy.ndarray or None
- param sunsensor_readings:
Sun sensor measurement in the body frame, shape
(3,).- type sunsensor_readings:
numpy.ndarray or None
- param B_ECI:
Reference magnetic field vector in ECI (or inertial) frame, shape
(3,).- type B_ECI:
numpy.ndarray or None
- param S_ECI:
Reference sun direction vector in ECI (or inertial) frame, shape
(3,).- type S_ECI:
numpy.ndarray or None
- param os:
Current orbital state (included for interface consistency).
- type os:
- param q:
Optional initial quaternion, shape
(4,). If provided, Wahba’s problem is skipped.- type q:
numpy.ndarray or None
- raises RuntimeError:
If no valid vector measurements are available for Wahba initialization.
- return:
Updated full augmented state vector (same length as
x_hat.val).- rtype:
numpy.ndarray
- Parameters:
gyro_readings (ndarray | None)
mtm_readings (ndarray | None)
sunpair_readings (ndarray | None)
sunsensor_readings (ndarray | None)
B_ECI (ndarray | None)
S_ECI (ndarray | None)
os (Orbital_State)
q (ndarray | None)
- reset(J2000, x_hat, P_hat, Q_hat, dt=1, cross_term=False)[source]¶
Reset the estimator state, covariance, and process noise.
This method validates dimensional consistency between the full augmented state vector \(\mathbf{x}\in\mathbb{R}^N\) and the covariance/process-noise matrices, stores the result into
EstimatedArraycontainers, and synchronizes the internal satellite model viamatch_estimate().Dimension consistency¶
The expected state length is
\[N = 7 + n_{RW} + n_{ab} + n_{sb} + n_{dp},\]where the counts are taken from the supplied
EstimatedSatellite.Covariance representation follows one of two conventions:
Reduced attitude space (default,
quat_as_vec=False):\[P,\;Q \in \mathbb{R}^{(N-1)\times(N-1)}.\]Full quaternion space (
quat_as_vec=True):\[P,\;Q \in \mathbb{R}^{N\times N}.\]
After validation, the reset procedure:
creates
EstimatedArrayinstances forx0_hatandx_hat,sets
useto allTrue(all states active),calls
match_estimate()to push the reset estimate into the satellite model.
- param J2000:
Time in seconds since J2000 corresponding to the new reset.
- type J2000:
float
- param x_hat:
New augmented state estimate \(\mathbf{x}\) of length \(N\).
- type x_hat:
numpy.ndarray
- param P_hat:
Covariance matrix, reduced or full depending on
quat_as_vec.- type P_hat:
numpy.ndarray
- param Q_hat:
Process-noise covariance matrix, same shape convention as
P_hat.- type Q_hat:
numpy.ndarray
- param dt:
Propagation time step \(\Delta t\) in seconds used for satellite model synchronization.
- type dt:
float
- param cross_term:
Whether the estimator should preserve cross-covariance blocks between bias/parameter groups in
update().- type cross_term:
bool
- raises ValueError:
If
x_hatlength is inconsistent with the satellite model.- raises ValueError:
If
P_hatorQ_hatshapes do not match the required convention.- return:
None.- rtype:
None
- Parameters:
J2000 (float)
x_hat (ndarray)
P_hat (ndarray)
Q_hat (ndarray)
dt (float)
cross_term (bool)
- Return type:
None
- update(u, sensors, os)[source]¶
High-level estimator update wrapper.
This method delegates the actual filtering step to a subclass-defined
update_core(), optionally enforces a block-structured covariance, updates the stored estimatex_hat, and synchronizes the satellite model viamatch_estimate().Delegation to subclass filter¶
Subclasses must implement
update_coreand return anEstimatedArraycontaining:val: full augmented state \(\hat{\mathbf{x}}\),cov: covariance in reduced coordinates (unlessquat_as_vec=True),int_cov: process-noise covariance (often unchanged).
Previous orbital state handling¶
If
prev_oshas not been initialized (prev_os.J2000 == 0), it is set to the providedOrbital_Stateoson the first call.Optional covariance block-zeroing¶
If
cross_termisFalse, this method zeros cross-covariance blocks between selected groups to enforce a block structure. Let the reduced covariance be partitioned as\[\begin{split}P = \begin{bmatrix} P_{xx} & P_{x,a} & P_{x,s} & P_{x,d} \\ P_{a,x} & P_{aa} & P_{a,s} & P_{a,d} \\ P_{s,x} & P_{s,a} & P_{ss} & P_{s,d} \\ P_{d,x} & P_{d,a} & P_{d,s} & P_{dd} \end{bmatrix},\end{split}\]where:
adenotes actuator-bias states,sdenotes attitude-sensor-bias states,ddenotes disturbance parameters.
Then the enforced structure is:
\[P_{a,s}=P_{s,a}^\top=\mathbf{0},\quad P_{a,d}=P_{d,a}^\top=\mathbf{0},\quad P_{s,d}=P_{d,s}^\top=\mathbf{0}.\]The index ranges are derived from:
state_len,act_bias_len,att_sens_bias_len,dist_param_len.
Committing the estimate¶
The new estimate is written back into
x_hatusing a mask over the reduced covariance space returned bycov_use(). Subselection and reinsertion of covariance/process-noise blocks relies onsquare_mat_sections().- param u:
Control input vector applied to the satellite (e.g., RW commands).
- type u:
numpy.ndarray
- param sensors:
Collection of sensor measurement vectors used by the estimator. The stacking/order convention is defined by the subclass and the satellite model.
- type sensors:
list[numpy.ndarray]
- param os:
Current orbital/environmental state used for propagation and prediction.
- type os:
- return:
Updated full augmented state estimate \(\hat{\mathbf{x}}\) (stored in
x_hat.val).- rtype:
numpy.ndarray
- Parameters:
u (ndarray)
sensors (List[ndarray])
os (Orbital_State)
- Return type:
ndarray
- Parameters:
est_sat (EstimatedSatellite)
J2000 (float)
x_hat (ndarray)
P_hat (ndarray)
Q_hat (ndarray)
dt (float)
cross_term (bool)
quat_as_vec (bool)