ADCS.estimators.orbit_estimators.orbit_estimator module¶
- class ADCS.estimators.orbit_estimators.orbit_estimator.Orbit_Estimator(est_sat, dt=1.0)[source]¶
Bases:
ABCAbstract base class for orbit determination (OD) algorithms.
This class defines the common interface and conceptual model for all orbit estimators used within the ADCS software stack. An orbit estimator is responsible for estimating the satellite orbital state vector in an inertial reference frame using a combination of dynamical propagation and sensor measurements.
The estimated orbital state is defined as the 6-dimensional state vector
\[\begin{split}\mathbf{x} = \begin{bmatrix} \mathbf{r} \\ \mathbf{v} \end{bmatrix} \in \mathbb{R}^6\end{split}\]where:
\(\mathbf{r} \in \mathbb{R}^3\) is the position vector in the Earth-Centered Inertial (ECI) frame
\(\mathbf{v} \in \mathbb{R}^3\) is the velocity vector in the same frame
The estimator maintains a probabilistic belief over this state in the form of:
An estimated mean state \(\hat{\mathbf{x}}\)
An associated covariance matrix \(\mathbf{P}\)
which are encapsulated by the
EstimatedOrbital_Statedata structure.This base class does not implement a specific estimation algorithm. Concrete subclasses (e.g. EKF, UKF, batch least squares) must implement the
update()andreset()methods.- Parameters:
est_sat (
EstimatedSatellite)dt (float)
- abstractmethod reset(**kwargs)[source]¶
Reset the estimator internal state and covariance.
This method re-initializes the estimator without requiring a new instance to be created. Concrete implementations should use this method to:
Define the initial state estimate \(\hat{\mathbf{x}}_0\)
Initialize the covariance matrix \(\mathbf{P}_0\)
Configure process noise models and tuning parameters
Typical reset behavior may include:
\[\hat{\mathbf{x}} \leftarrow \hat{\mathbf{x}}_0, \qquad \mathbf{P} \leftarrow \mathbf{P}_0\]The exact parameters required depend on the specific estimator implementation (e.g. EKF vs. batch estimator) and are passed via keyword arguments.
- Parameters:
kwargs (dict) – Implementation-specific initialization parameters such as initial state vectors, covariance matrices, or noise tuning values.
- Returns:
None
- Return type:
None
- abstractmethod update(GPS_measurements, J2000)[source]¶
Propagate and update the orbital state estimate using sensor measurements.
This method performs one full estimation cycle consisting of:
Time Update (Prediction) The previous state estimate \(\hat{\mathbf{x}}_{k-1}\) is propagated forward in time according to the orbital dynamics model:
\[\hat{\mathbf{x}}_k^{-} = f\!\left(\hat{\mathbf{x}}_{k-1}, \Delta t\right)\]Measurement Update (Correction) The predicted state is corrected using available GPS measurements \(\mathbf{z}_k\):
\[\hat{\mathbf{x}}_k = \hat{\mathbf{x}}_k^{-} + \mathbf{K}_k \left( \mathbf{z}_k - h\!\left(\hat{\mathbf{x}}_k^{-}\right) \right)\]
where:
\(f(\cdot)\) is the nonlinear orbital dynamics model
\(h(\cdot)\) is the measurement model
\(\mathbf{K}_k\) is the estimator-specific gain matrix
The measurement list may contain multiple GPS observations at the same epoch, each expressed either as:
Position-only measurements: \(\mathbf{z}_k \in \mathbb{R}^3\)
Position-velocity measurements: \(\mathbf{z}_k \in \mathbb{R}^6\)
All measurements are assumed to be expressed in the ECI frame and time-tagged at the provided J2000 epoch.
- Parameters:
GPS_measurements (list[numpy.ndarray]) – List of GPS measurement vectors used to update the orbital state estimate.
J2000 (float) – Current epoch time expressed in seconds since J2000.
- Returns:
Updated estimated orbital state containing the state vector \(\hat{\mathbf{x}}_k\) and covariance matrix \(\mathbf{P}_k\).
- Return type:
EstimatedOrbital_State