Source code for ADCS.satellite_hardware.disturbances.dipole_disturbance

__all__ = ["Dipole_Disturbance"]

import numpy as np
from typing import TYPE_CHECKING
from ADCS.satellite_hardware.disturbances.disturbance import Disturbance
from ADCS.satellite_hardware.errors.noise import Noise
from ADCS.orbits.orbital_state import Orbital_State
from ADCS.helpers.math_helpers import normalize

[docs] class Dipole_Disturbance(Disturbance): r""" Magnetic 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 .. math:: \mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b. where :math:`\mathbf{m}_d` Residual magnetic dipole vector expressed in the spacecraft body frame [A·m²]. :math:`\mathbf{B}_b` Geomagnetic field vector expressed in the spacecraft body frame [T]. :math:`\mathbf{T}_d` Resulting magnetic disturbance torque acting on the spacecraft [N·m]. The geomagnetic field is provided by :class:`~ADCS.orbits.orbital_state.Orbital_State` and rotated into the body frame using the spacecraft attitude quaternion. Noise Model ----------- The residual dipole may be perturbed by a stochastic noise process, .. math:: \mathbf{m}_d(t) = \mathbf{m}_{d,0} + \mathbf{n}(t), where :math:`\mathbf{n}(t)` is generated by :class:`~ADCS.satellite_hardware.errors.noise.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 """ def __init__(self, dipole_torque: np.ndarray, noise: Noise = None, estimate_dist: bool = False): r""" Initialize the magnetic dipole disturbance model. This constructor defines the nominal residual magnetic dipole and optionally attaches a stochastic noise generator. The dipole vector is assumed constant in the body frame, except for optional noise. :param dipole_torque: Nominal residual magnetic dipole vector expressed in body coordinates [A·m²], shape ``(3,)``. :type dipole_torque: numpy.ndarray :param noise: Noise generator used to perturb the dipole vector at each update step. If ``None``, a zero-noise model is used. :type noise: ADCS.satellite_hardware.errors.noise.Noise or None :param estimate_dist: Enables dipole vector estimation through the disturbance framework. :type estimate_dist: bool :return: None :rtype: None """ self.torque_nominal = dipole_torque if noise: self.noise = noise else: self.noise = Noise() self.current_torque = self.torque_nominal.copy() super().__init__(estimate_dist=estimate_dist, estimated_vector_length=3)
[docs] def update(self) -> None: r""" Update the residual magnetic dipole vector. At each simulation step, the dipole vector is updated according to .. math:: \mathbf{m}_d(t) = \mathbf{m}_{d,0} + \mathbf{n}(t), where :math:`\mathbf{n}(t)` is drawn from the configured :class:`~ADCS.satellite_hardware.errors.noise.Noise` model. This method must be called **once per propagation step** prior to torque evaluation. :return: None :rtype: None """ self.current_torque = self.torque_nominal + self.noise.get_noise()
[docs] def torque(self, x: np.ndarray, os: Orbital_State) -> np.ndarray: r""" Compute the magnetic dipole disturbance torque. The disturbance torque is computed in the spacecraft body frame as .. math:: \mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b, where the geomagnetic field :math:`\mathbf{B}_b` is provided by :class:`~ADCS.orbits.orbital_state.Orbital_State`. :param x: Full spacecraft state vector containing the attitude quaternion. :type x: numpy.ndarray :param os: Orbital state object providing the body-frame magnetic field. :type os: ADCS.orbits.orbital_state.Orbital_State :return: Disturbance torque vector in the body frame [N·m], shape ``(3,)``. :rtype: numpy.ndarray """ vecs = os.get_state_vector(x=x) B_B = vecs["b"] return np.cross(self.current_torque, B_B)
[docs] def torque_qjac(self, x: np.ndarray, os: Orbital_State) -> np.ndarray: r""" Jacobian of the disturbance torque with respect to the attitude quaternion. Since .. math:: \mathbf{T}_d(\mathbf{q}) = \mathbf{m}_d \times \mathbf{B}_b(\mathbf{q}), the quaternion Jacobian is .. math:: \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 :class:`~ADCS.orbits.orbital_state.Orbital_State`. :param x: Spacecraft state vector containing the attitude quaternion. :type x: numpy.ndarray :param os: Orbital state provider of magnetic field derivatives. :type os: ADCS.orbits.orbital_state.Orbital_State :return: Quaternion Jacobian of the torque, shape ``(3, 4)``. :rtype: numpy.ndarray """ vecs = os.get_state_vector(x=x) db_body__dq = vecs["db"] return np.cross(self.current_torque, db_body__dq)
[docs] def torque_qqhess(self, x: np.ndarray, os: Orbital_State) -> np.ndarray: r""" Hessian of the disturbance torque with respect to the attitude quaternion. Given .. math:: \mathbf{T}_d(\mathbf{q}) = \mathbf{m}_d \times \mathbf{B}_b(\mathbf{q}), the second derivative is .. math:: \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. :param x: Spacecraft state vector containing the attitude quaternion. :type x: numpy.ndarray :param os: Orbital state provider of magnetic field Hessians. :type os: ADCS.orbits.orbital_state.Orbital_State :return: Quaternion Hessian of the torque, shape ``(3, 4, 4)``. :rtype: numpy.ndarray """ vecs = os.get_state_vector(x=x) ddb_body__dqdq = vecs["ddb"] return np.cross(self.current_torque, ddb_body__dqdq)
[docs] def torque_valjac(self, x: np.ndarray, os: Orbital_State) -> np.ndarray: r""" Jacobian of the disturbance torque with respect to the dipole vector. From the cross-product identity .. math:: \mathbf{T}_d = \mathbf{m}_d \times \mathbf{B}_b, the Jacobian with respect to :math:`\mathbf{m}_d` is .. math:: \frac{\partial \mathbf{T}_d}{\partial \mathbf{m}_d} = [\,\mathbf{B}_b \times\,], where :math:`[\,\cdot\times\,]` denotes the skew-symmetric cross-product matrix. This Jacobian is used when estimating the residual magnetic dipole. :param x: Full spacecraft state vector. :type x: numpy.ndarray :param os: Orbital state providing the body-frame magnetic field. :type os: ADCS.orbits.orbital_state.Orbital_State :return: Dipole Jacobian of the torque, shape ``(3, 3)``. :rtype: numpy.ndarray """ vecs = os.get_state_vector(x=x) B_B = vecs["b"] return np.cross(np.eye(3), B_B)
[docs] def torque_qvalhess(self, x: np.ndarray, os: Orbital_State) -> np.ndarray: r""" Mixed second derivative of the disturbance torque with respect to quaternion and dipole vector. Using the skew-symmetric operator, .. math:: \mathbf{T}_d = [\,\mathbf{m}_d \times\,]\mathbf{B}_b(\mathbf{q}), the mixed derivative is .. math:: \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. :param x: Spacecraft state vector containing the attitude quaternion. :type x: numpy.ndarray :param os: Orbital state providing magnetic field quaternion derivatives. :type os: ADCS.orbits.orbital_state.Orbital_State :return: Mixed quaternion–dipole Hessian, shape ``(4, 3, 3)``. :rtype: numpy.ndarray """ vecs = os.get_state_vector(x=x) db_body__dq = vecs["db"] return np.cross(np.expand_dims(np.eye(3), 0), np.expand_dims(db_body__dq, 1))