ADCS.satellite_hardware.sensors.sunpair module

class ADCS.satellite_hardware.sensors.sunpair.SunPair(axis, efficiency, sample_time=0.1, bias=None, noise=None, estimate_bias=False)[source]

Bases: Sensor

Dual-hemisphere coarse Sun sensor model.

This class models a pair of opposing coarse Sun sensors aligned along a single body-frame axis. The two sensors together provide a single scalar measurement proportional to the projection of the Sun direction onto the sensor axis, scaled by a hemisphere-dependent efficiency.

The class conforms to the generic sensor interface defined by Sensor.

Conceptual model

Let

Symbol

Description

\(\hat{\mathbf{a}}\)

Unit sensor axis (body frame)

\(\hat{\mathbf{s}}\)

Unit Sun direction (body frame)

\(\eta_\text{front}\)

Efficiency for +axis hemisphere

\(\eta_\text{back}\)

Efficiency for −axis hemisphere

The Sun direction expressed in the body frame is obtained from the orbital state as

\[\hat{\mathbf{s}} = \frac{\mathbf{s} - \mathbf{r}} {\lVert \mathbf{s} - \mathbf{r} \rVert},\]

where \(\mathbf{r}\) is the spacecraft position and \(\mathbf{s}\) is the Sun position, both provided by get_state_vector().

The clean (ideal) measurement is defined as

\[\begin{split}y_{\text{clean}} = \begin{cases} (\hat{\mathbf{a}}^\top \hat{\mathbf{s}})\,\eta_\text{front}, & \hat{\mathbf{a}}^\top \hat{\mathbf{s}} > 0, \\ (\hat{\mathbf{a}}^\top \hat{\mathbf{s}})\,\eta_\text{back}, & \hat{\mathbf{a}}^\top \hat{\mathbf{s}} \le 0. \end{cases}\end{split}\]

If the spacecraft is not illuminated by the Sun, i.e.,

\[\texttt{os.is\_sunlit()} = \text{False},\]

the measurement is undefined and the sensor returns NaN.

Measurement with errors

Including bias and noise, the full sensor output is

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

where

  • \(b\) is an additive scalar bias modeled by Bias,

  • \(n\) is additive noise modeled by Noise.

Notes

  • This is a coarse Sun sensor, intended for low-accuracy attitude determination.

  • The output dimension is scalar, so output_length = 1.

  • When the spacecraft is in eclipse, all Jacobians are identically zero.

basestate_jac(x, os)[source]

Jacobian of the clean Sun-sensor measurement with respect to the base ADCS state.

The base state is defined as

\[\mathbf{x} = [\omega_x, \omega_y, \omega_z, q_0, q_1, q_2, q_3]^\top,\]

where \(\boldsymbol{\omega}\) is the body angular rate and \(\mathbf{q}\) is the attitude quaternion.

Because the Sun direction in the body frame depends on spacecraft attitude, this Jacobian is computed numerically using central finite differences:

\[\frac{\partial y}{\partial x_i} \approx \frac{f(x_i + \varepsilon) - f(x_i - \varepsilon)}{2\varepsilon},\]

with \(\varepsilon = 10^{-6}\) and \(f(\cdot)\) defined by _clean_scalar().

If the spacecraft is not sunlit, the clean measurement is identically zero and all partial derivatives are zero.

Parameters:
  • x (numpy.ndarray) – Full 7-element ADCS state vector.

  • os (Orbital_State) – Orbital state providing lighting conditions and Sun/spacecraft geometry.

Returns:

Jacobian of the clean measurement with respect to the base state, with shape (7, 1).

Return type:

numpy.ndarray

bias_jac(x, os)[source]

Jacobian of the measurement with respect to the Sun-sensor bias.

When a bias model is present, the measurement model is

\[z = y + b,\]

where \(b\) is a scalar bias. The Jacobian is therefore

\[\frac{\partial z}{\partial b} = 1.\]

If no bias model exists, an empty Jacobian is returned.

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

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

Returns:

A (1,1) identity matrix if a bias exists, otherwise a (0,1) empty array.

Return type:

numpy.ndarray

clean_reading(x, os)[source]

Compute the clean (noise- and bias-free) Sun sensor measurement.

The clean measurement is computed according to the dual-hemisphere model described in the class documentation. If the spacecraft is in eclipse (os.is_sunlit() == False), the clean measurement is undefined and NaN is returned.

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

  • os (Orbital_State) – Orbital state providing spacecraft position, Sun position, and lighting conditions.

Returns:

Clean scalar Sun-sensor measurement wrapped in a 1-element array, or NaN if the spacecraft is not sunlit.

Return type:

numpy.ndarray

Parameters:
  • axis (ndarray)

  • efficiency (Tuple[float, float])

  • sample_time (float)

  • bias (Bias)

  • noise (Noise)

  • estimate_bias (bool)