ADCS.satellite_hardware.sensors.gps module

class ADCS.satellite_hardware.sensors.gps.GPS(sample_time=0.1, bias=None, noise=None, estimate_bias=False)[source]

Bases: Sensor

Global Positioning System (GPS) position–velocity sensor model.

This class implements a GPS receiver that provides a 6-element measurement consisting of the spacecraft position and velocity expressed in the Earth-Centered Earth-Fixed (ECEF) reference frame.

The GPS sensor follows the generic sensor model defined in Sensor.

Measurement model

The clean (ideal) GPS measurement is defined as

\[\begin{split}\mathbf{z}_{\text{clean}} = \begin{bmatrix} \mathbf{r}_{\mathrm{ECEF}} \\ \mathbf{v}_{\mathrm{ECEF}} \end{bmatrix} \in \mathbb{R}^6,\end{split}\]

where:

Symbol

Description

\(\mathbf{r}\)

Satellite position vector

\(\mathbf{v}\)

Satellite velocity vector

ECEF

Earth-Centered Earth-Fixed frame

The full measurement includes bias and noise:

\[\mathbf{z} = \mathbf{z}_{\text{clean}} + \mathbf{b} + \mathbf{n},\]

where:

  • \(\mathbf{b}\) is a 6-element GPS bias vector modeled using Bias

  • \(\mathbf{n}\) is a 6-element measurement noise vector modeled using Noise

param sample_time:

Sampling period of the GPS sensor in seconds.

type sample_time:

float

param bias:

GPS bias model. If None, a zero 6-element bias is used.

type bias:

Bias or None

param noise:

GPS noise model. If None, a zero 6-element noise model is used.

type noise:

Noise or None

param estimate_bias:

Indicates whether the GPS bias is estimated as part of the system state.

type estimate_bias:

bool

return:

None

rtype:

None

Notes

  • This sensor is not an attitude sensor.

  • Position is taken directly from the orbital state in ECEF coordinates.

  • Velocity is transformed from ECI to ECEF using eci_to_ecef().

bias_jac(x, os)[source]

Jacobian of the GPS measurement with respect to the GPS bias state.

The GPS measurement is modeled as

\[\mathbf{z} = \mathbf{z}_{\text{clean}} + \mathbf{b},\]

where \(\mathbf{b} \in \mathbb{R}^6\) is the GPS bias vector.

Therefore, the Jacobian with respect to the bias is

\[\mathbf{H}_b = \frac{\partial \mathbf{z}}{\partial \mathbf{b}} = I_6.\]
Parameters:
  • x (numpy.ndarray) – Full system state vector (unused).

  • os (Orbital_State) – Orbital state object (unused).

Returns:

6 × 6 identity matrix if a bias model exists; otherwise an empty 0 × 6 matrix.

Return type:

numpy.ndarray

clean_reading(x, os)[source]

Compute the clean GPS measurement (position and velocity in ECEF).

This method constructs the ideal GPS output using the orbital state:

  • Position is obtained directly from os.ECEF

  • Velocity is obtained from os.V (ECI) and rotated into ECEF using eci_to_ecef()

Mathematically,

\[\begin{split}\mathbf{z}_{\text{clean}} = \begin{bmatrix} \mathbf{r}_{\mathrm{ECEF}} \\ C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}} \, \mathbf{v}_{\mathrm{ECI}} \end{bmatrix},\end{split}\]

where \(C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}}\) is the coordinate transformation matrix from the inertial to Earth-fixed frame.

Parameters:
  • x (numpy.ndarray) – Full system state vector. This argument is unused by the GPS model.

  • os (Orbital_State) – Orbital state providing position, velocity, and frame transforms.

Returns:

Clean GPS measurement vector [r_ECEF, v_ECEF].

Return type:

numpy.ndarray

orbitRV_jac(x, os)[source]

Jacobian of the GPS measurement with respect to orbital position and velocity states in the ECI frame.

The coordinate transformations are:

  • Position: \(\mathbf{r}_{\mathrm{ECEF}} = C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}} \mathbf{r}_{\mathrm{ECI}}\)

  • Velocity: \(\mathbf{v}_{\mathrm{ECEF}} = C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}} \mathbf{v}_{\mathrm{ECI}}\)

The resulting Jacobian is block-diagonal:

\[\begin{split}\mathbf{H}_{rv} = \frac{\partial \mathbf{z}} {\partial \begin{bmatrix} \mathbf{r}_{\mathrm{ECI}} \\ \mathbf{v}_{\mathrm{ECI}} \end{bmatrix}} = \begin{bmatrix} C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}} & 0 \\ 0 & C_{\mathrm{ECI}\rightarrow\mathrm{ECEF}} \end{bmatrix}.\end{split}\]

The rotation matrix is constructed by applying eci_to_ecef() to the unit basis vectors defined in MathConstants.

Parameters:
  • x (numpy.ndarray) – Full system state vector (unused).

  • os (Orbital_State) – Orbital state providing the ECI→ECEF transformation.

Returns:

Block-diagonal Jacobian matrix of shape 6 × 6.

Return type:

numpy.ndarray

Parameters:
  • sample_time (float)

  • bias (Bias)

  • noise (Noise)

  • estimate_bias (bool)