ADCS.satellite_hardware.disturbances.prop_disturbance module

class ADCS.satellite_hardware.disturbances.prop_disturbance.Prop_Disturbance(torque_nominal, noise=None, estimate_dist=False)[source]

Bases: Disturbance

Propulsion-Induced Disturbance Torque Model

This class models propulsion-related disturbance torques acting on a spacecraft. Such torques typically arise from imperfect thrust alignment, residual thrust during coast phases, asymmetric propellant flow, or unmodeled reaction forces during maneuver execution.

The propulsion disturbance is modeled as a constant nominal torque with an optional additive stochastic noise component. Unlike environmental disturbances (e.g., gravity-gradient or aerodynamic drag), this torque does not depend on the spacecraft attitude or orbital state.

Mathematical Model

The propulsion disturbance torque is expressed as:

\[\mathbf{T}_{\mathrm{prop}}(t) = \mathbf{T}_0 + \mathbf{n}(t),\]

where:

Symbol

Description

\(\mathbf{T}_0\) | Nominal constant propulsion torque [N·m]

\(\mathbf{n}(t)\) | Zero-mean stochastic noise torque [N·m]

The noise term \(\mathbf{n}(t)\) is generated by a user-supplied noise model of type Noise.

Attitude Independence

Since \(\mathbf{T}_{\mathrm{prop}}\) does not depend on the attitude quaternion \(\mathbf{q}\), all attitude derivatives vanish:

\[\frac{\partial \mathbf{T}_{\mathrm{prop}}}{\partial \mathbf{q}} = \mathbf{0}_{3\times4}, \qquad \frac{\partial^2 \mathbf{T}_{\mathrm{prop}}}{\partial \mathbf{q}^2} = \mathbf{0}_{3\times4\times4}.\]

This makes the propulsion disturbance especially simple to include in linearized or second-order attitude dynamics formulations.

Parameters:
  • torque_nominal (numpy.ndarray) – Nominal constant propulsion disturbance torque vector.

  • noise (Noise) – Noise model providing stochastic torque perturbations.

  • estimate_dist (bool)

torque(x, os)[source]

Return the current propulsion disturbance torque.

This method simply returns the internally stored disturbance torque that was most recently updated by update().

The torque is independent of:

  • the attitude quaternion in x

  • the orbital state os

These parameters are accepted only to maintain interface consistency with other disturbance models derived from Disturbance.

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

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

Returns:

Current propulsion disturbance torque [N·m], shape (3,).

Return type:

numpy.ndarray

torque_qjac()[source]

Compute the Jacobian of the propulsion disturbance torque with respect to the attitude quaternion.

Because the propulsion disturbance torque is constant and does not depend on the attitude quaternion \(\mathbf{q}\), the Jacobian is identically zero:

\[\frac{\partial \mathbf{T}_{\mathrm{prop}}}{\partial \mathbf{q}} = \mathbf{0}_{3\times4}.\]
Returns:

Quaternion Jacobian matrix of zeros, shape (3, 4).

Return type:

numpy.ndarray

torque_qqHess()[source]

Compute the Hessian of the propulsion disturbance torque with respect to the attitude quaternion.

Since \(\mathbf{T}_{\mathrm{prop}}\) is constant, all second-order derivatives vanish:

\[\frac{\partial^2 \mathbf{T}_{\mathrm{prop}}}{\partial \mathbf{q}^2} = \mathbf{0}_{3\times4\times4}.\]
Returns:

Quaternion Hessian tensor of zeros, shape (3, 4, 4).

Return type:

numpy.ndarray

update()[source]

Update the current propulsion disturbance torque.

This method draws a new noise realization from the noise model and updates the current disturbance torque according to:

\[\mathbf{T}_{\mathrm{prop}}(t) = \mathbf{T}_0 + \mathbf{n}(t),\]

where \(\mathbf{n}(t)\) is provided by get_noise().

This method should typically be called once per simulation or control update step.

Returns:

None

Return type:

None