ADCS.satellite_hardware.disturbances.dipole_disturbance module¶
- class ADCS.satellite_hardware.disturbances.dipole_disturbance.Dipole_Disturbance(dipole_torque, noise=None, estimate_dist=False)[source]¶
Bases:
DisturbanceMagnetic Dipole Disturbance Model.
This class models the passive disturbance torque caused by a residual (parasitic) magnetic dipole fixed in the spacecraft body interacting with the Earth’s geomagnetic field.
Physical Background¶
A spacecraft with a residual magnetic dipole immersed in a magnetic field experiences a torque given by
\[\mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b.\]where
- \(\mathbf{m}_d\)
Residual magnetic dipole vector expressed in the spacecraft body frame [A·m²].
- \(\mathbf{B}_b\)
Geomagnetic field vector expressed in the spacecraft body frame [T].
- \(\mathbf{T}_d\)
Resulting magnetic disturbance torque acting on the spacecraft [N·m].
The geomagnetic field is provided by
Orbital_Stateand rotated into the body frame using the spacecraft attitude quaternion.Noise Model¶
The residual dipole may be perturbed by a stochastic noise process,
\[\mathbf{m}_d(t) = \mathbf{m}_{d,0} + \mathbf{n}(t),\]where \(\mathbf{n}(t)\) is generated by
Noise.- param dipole_torque:
Nominal residual magnetic dipole vector in body coordinates [A·m²].
- type dipole_torque:
numpy.ndarray
- param noise:
Optional noise model used to perturb the dipole vector.
- type noise:
ADCS.satellite_hardware.errors.noise.Noise or None
- param estimate_dist:
Enables estimation of the dipole disturbance.
- type estimate_dist:
bool
- torque(x, os)[source]¶
Compute the magnetic dipole disturbance torque.
The disturbance torque is computed in the spacecraft body frame as
\[\mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b,\]where the geomagnetic field \(\mathbf{B}_b\) is provided by
Orbital_State.- Parameters:
x (numpy.ndarray) – Full spacecraft state vector containing the attitude quaternion.
os (ADCS.orbits.orbital_state.Orbital_State) – Orbital state object providing the body-frame magnetic field.
- Returns:
Disturbance torque vector in the body frame [N·m], shape
(3,).- Return type:
numpy.ndarray
- torque_qjac(x, os)[source]¶
Jacobian of the disturbance torque with respect to the attitude quaternion.
Since
\[\mathbf{T}_d(\mathbf{q}) = \mathbf{m}_d \times \mathbf{B}_b(\mathbf{q}),\]the quaternion Jacobian is
\[\frac{\partial \mathbf{T}_d}{\partial \mathbf{q}} = \mathbf{m}_d \times \frac{\partial \mathbf{B}_b}{\partial \mathbf{q}}.\]The magnetic field derivative is supplied by
Orbital_State.- Parameters:
x (numpy.ndarray) – Spacecraft state vector containing the attitude quaternion.
os (ADCS.orbits.orbital_state.Orbital_State) – Orbital state provider of magnetic field derivatives.
- Returns:
Quaternion Jacobian of the torque, shape
(3, 4).- Return type:
numpy.ndarray
- torque_qqhess(x, os)[source]¶
Hessian of the disturbance torque with respect to the attitude quaternion.
Given
\[\mathbf{T}_d(\mathbf{q}) = \mathbf{m}_d \times \mathbf{B}_b(\mathbf{q}),\]the second derivative is
\[\frac{\partial^2 \mathbf{T}_d}{\partial \mathbf{q}^2} = \mathbf{m}_d \times \frac{\partial^2 \mathbf{B}_b}{\partial \mathbf{q}^2}.\]This quantity is required for second-order attitude estimation or optimization methods.
- Parameters:
x (numpy.ndarray) – Spacecraft state vector containing the attitude quaternion.
os (ADCS.orbits.orbital_state.Orbital_State) – Orbital state provider of magnetic field Hessians.
- Returns:
Quaternion Hessian of the torque, shape
(3, 4, 4).- Return type:
numpy.ndarray
- torque_qvalhess(x, os)[source]¶
Mixed second derivative of the disturbance torque with respect to quaternion and dipole vector.
Using the skew-symmetric operator,
\[\mathbf{T}_d = [\,\mathbf{m}_d \times\,]\mathbf{B}_b(\mathbf{q}),\]the mixed derivative is
\[\frac{\partial^2 \mathbf{T}_d} {\partial \mathbf{q}\,\partial \mathbf{m}_d} = \left[\,\frac{\partial \mathbf{B}_b}{\partial \mathbf{q}} \times\,\right].\]This term is relevant in joint state–parameter estimation frameworks.
- Parameters:
x (numpy.ndarray) – Spacecraft state vector containing the attitude quaternion.
os (ADCS.orbits.orbital_state.Orbital_State) – Orbital state providing magnetic field quaternion derivatives.
- Returns:
Mixed quaternion–dipole Hessian, shape
(4, 3, 3).- Return type:
numpy.ndarray
- torque_valjac(x, os)[source]¶
Jacobian of the disturbance torque with respect to the dipole vector.
From the cross-product identity
\[\mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b,\]the Jacobian with respect to \(\mathbf{m}_d\) is
\[\frac{\partial \mathbf{T}_d}{\partial \mathbf{m}_d} = [\,\mathbf{B}_b \times\,],\]where \([\,\cdot\times\,]\) denotes the skew-symmetric cross-product matrix.
This Jacobian is used when estimating the residual magnetic dipole.
- Parameters:
x (numpy.ndarray) – Full spacecraft state vector.
os (ADCS.orbits.orbital_state.Orbital_State) – Orbital state providing the body-frame magnetic field.
- Returns:
Dipole Jacobian of the torque, shape
(3, 3).- Return type:
numpy.ndarray
- update()[source]¶
Update the residual magnetic dipole vector.
At each simulation step, the dipole vector is updated according to
\[\mathbf{m}_d(t) = \mathbf{m}_{d,0} + \mathbf{n}(t),\]where \(\mathbf{n}(t)\) is drawn from the configured
Noisemodel.This method must be called once per propagation step prior to torque evaluation.
- Returns:
None
- Return type:
None
- Parameters:
dipole_torque (ndarray)
noise (Noise)
estimate_dist (bool)