ADCS.satellite_hardware.disturbances.gg_disturbance module

class ADCS.satellite_hardware.disturbances.gg_disturbance.GG_Disturbance[source]

Bases: Disturbance

Gravity-Gradient Disturbance Torque Model

This class implements the gravity-gradient (GG) torque acting on a rigid spacecraft in orbit about the Earth. Gravity-gradient torque arises from the non-uniform gravitational field acting on a spacecraft with an extended mass distribution and is one of the dominant passive disturbance torques for elongated or inertia-asymmetric spacecraft in low Earth orbit (LEO).

The model assumes:

  • A rigid spacecraft with constant inertia tensor expressed in the body frame

  • A central gravitational field characterized by Earth’s gravitational parameter \(\mu_e\)

  • The spacecraft attitude is represented implicitly through the mapping of orbital position into the body frame

All quantities are computed in the body frame.

Orbital Coupling

The disturbance depends on the body-frame position vector of the spacecraft center of mass relative to the Earth, provided by:

Orbital_State

via get_state_vector().

Inertia Properties

The spacecraft inertia tensor about the center of mass is provided by:

Satellite

via the attribute sat.J_0.

This class provides:

  • the gravity-gradient torque

  • its Jacobian with respect to the attitude quaternion

  • its Hessian with respect to the attitude quaternion

These derivatives are required for high-order attitude dynamics, sensitivity analysis, and second-order optimization or estimation methods.

torque(sat, x, os)[source]

Compute the gravity-gradient torque in the body frame.

Let \(\mathbf{R}_B\) be the position vector from the Earth center to the spacecraft center of mass, expressed in the body frame. Define the unit radial vector:

\[\hat{\mathbf{r}} = \frac{\mathbf{R}_B}{\|\mathbf{R}_B\|}\]

and the nadir-pointing direction:

\[\mathbf{n} = -\hat{\mathbf{r}}.\]

The classical gravity-gradient torque acting on a rigid spacecraft is:

\[\mathbf{T}_{\mathrm{GG}} = \frac{3\mu_e}{\|\mathbf{R}_B\|^3} \, \mathbf{n} \times \left( \mathbf{J}_0 \mathbf{n} \right),\]

where:

  • \(\mu_e\) is Earth’s gravitational parameter (mu_e)

  • \(\mathbf{J}_0\) is the spacecraft inertia tensor about COM in the body frame

Dependencies

  • \(\mathbf{R}_B\) is obtained from get_state_vector()

  • The attitude quaternion contained in x determines the body-frame orientation of \(\mathbf{R}_B\)

Parameters:
  • sat (Satellite) – Satellite instance providing the inertia tensor sat.J_0.

  • x (numpy.ndarray) – Full spacecraft state containing the attitude quaternion.

  • os (Orbital_State) – Orbital state provider supplying the body-frame position vector "r".

Returns:

Gravity-gradient torque vector in the body frame, shape (3,).

Return type:

numpy.ndarray

torque__qqhess(sat, x, os)[source]

Compute the Hessian of the gravity-gradient torque with respect to the attitude quaternion.

This method evaluates the second derivative tensor:

\[\frac{\partial^2 \mathbf{T}_{\mathrm{GG}}}{\partial \mathbf{q}^2},\]

which has shape (3,4,4) and is required for second-order sensitivity analysis, trajectory optimization, and higher-order attitude dynamics.

Using the decomposition:

\[\mathbf{T}_{\mathrm{GG}} = c(\mathbf{q})\,\mathbf{v}(\mathbf{q}),\]

the Hessian is obtained via repeated application of the product rule:

\[\frac{\partial^2 \mathbf{T}_{\mathrm{GG}}}{\partial \mathbf{q}^2} = \frac{\partial^2 c}{\partial \mathbf{q}^2} \otimes \mathbf{v} + \frac{\partial c}{\partial \mathbf{q}} \otimes \frac{\partial \mathbf{v}}{\partial \mathbf{q}} + \left(\cdot\right)^{\top} + c \, \frac{\partial^2 \mathbf{v}}{\partial \mathbf{q}^2},\]

where \((\cdot)^{\top}\) denotes the symmetric transpose with respect to the quaternion derivative indices.

Second-order geometric derivatives

The implementation relies on:

to compute second derivatives of normalized vectors and vector norms.

The second derivative of the nadir direction is:

\[\frac{\partial^2 \mathbf{n}}{\partial \mathbf{q}^2} = -\frac{\partial^2 \hat{\mathbf{r}}}{\partial \mathbf{q}^2}.\]

Mixed cross-product terms are explicitly symmetrized to ensure consistency with the analytical Hessian structure.

Parameters:
  • sat (Satellite) – Satellite instance providing the inertia tensor sat.J_0.

  • x (numpy.ndarray) – Full spacecraft state containing the attitude quaternion.

  • os (Orbital_State) – Orbital state provider supplying position and its first and second quaternion derivatives via "r", "dr", "ddr".

Returns:

Quaternion Hessian of gravity-gradient torque, shape (3, 4, 4).

Return type:

numpy.ndarray

torque_qvac(sat, x, os)[source]

Compute the Jacobian of the gravity-gradient torque with respect to the attitude quaternion.

The gravity-gradient torque can be written as:

\[\mathbf{T}_{\mathrm{GG}}(\mathbf{q}) = c(\mathbf{q}) \, \mathbf{v}(\mathbf{q}),\]

where:

\[c(\mathbf{q}) = \frac{3\mu_e}{\|\mathbf{R}_B(\mathbf{q})\|^3}, \qquad \mathbf{v}(\mathbf{q}) = \mathbf{n}(\mathbf{q}) \times \left(\mathbf{J}_0 \mathbf{n}(\mathbf{q})\right).\]

The Jacobian follows from the product rule:

\[\frac{\partial \mathbf{T}_{\mathrm{GG}}}{\partial \mathbf{q}} = \frac{\partial c}{\partial \mathbf{q}} \otimes \mathbf{v} + c \, \frac{\partial \mathbf{v}}{\partial \mathbf{q}}.\]

Intermediate derivatives

The unit vector derivative is computed using:

The nadir direction derivative is:

\[\frac{\partial \mathbf{n}}{\partial \mathbf{q}} = -\frac{\partial \hat{\mathbf{r}}}{\partial \mathbf{q}}.\]

The derivative of the vector cross-product term is:

\[\frac{\partial \mathbf{v}}{\partial \mathbf{q}} = \frac{\partial \mathbf{n}}{\partial \mathbf{q}} \times (\mathbf{J}_0 \mathbf{n}) + \mathbf{n} \times \left(\mathbf{J}_0 \frac{\partial \mathbf{n}}{\partial \mathbf{q}}\right).\]

The resulting Jacobian has shape (4,3) or (3,4) depending on convention; this implementation returns a matrix consistent with the internal ADCS quaternion ordering.

Parameters:
  • sat (Satellite) – Satellite instance providing the inertia tensor sat.J_0.

  • x (numpy.ndarray) – Full spacecraft state containing the attitude quaternion.

  • os (Orbital_State) – Orbital state provider supplying position and its quaternion derivatives via "r", "dr".

Returns:

Quaternion Jacobian of gravity-gradient torque.

Return type:

numpy.ndarray