ADCS.satellite_hardware.actuators.magnetotorquer module

class ADCS.satellite_hardware.actuators.magnetotorquer.MTQ(axis, max_torque, bias=None, noise=None, estimate_bias=False)[source]

Bases: Actuator

Magnetorquer (MTQ) actuator model

This class models a single-axis magnetorquer that generates body torque from the interaction between a commanded magnetic dipole moment and the local geomagnetic field.

The model extends Actuator.

Physical model

The torque produced by a magnetic dipole \(\mathbf{m}\) in a magnetic field \(\mathbf{B}_{\mathcal{B}}\) (expressed in the body frame) is

\[\boldsymbol{\tau}_{\mathrm{MTQ}} = -\,\mathbf{B}_{\mathcal{B}} \times \mathbf{m}.\]

The dipole is constrained to a fixed body-axis \(\mathbf{a}\) (unit vector) and commanded with a scalar magnitude \(u\) (with optional scalar bias \(b\)):

\[\mathbf{m} = \mathbf{a}\,(u + b).\]

Combining the two gives the actuation model used by torque():

\[\boldsymbol{\tau}_{\mathrm{MTQ}} = -(\mathbf{B}_{\mathcal{B}} \times \mathbf{a})\,(u+b) + \mathbf{n},\]

where \(\mathbf{n}\) is an additive noise term (if enabled).

Symbols

Symbol

Meaning

\(\mathbf{B}_{\mathcal{B}}\)

Earth’s magnetic field expressed in the body frame [T]

\(\mathbf{m}\)

Magnetic dipole moment vector [A·m²]

\(\mathbf{a}\)

Magnetorquer unit axis in the body frame

\(u\)

Commanded dipole magnitude [A·m²]

\(b\)

Bias in the commanded dipole (modeled by Bias)

\(\mathbf{n}\)

Additive actuator torque noise (modeled by Noise)

State dependence

The body-frame field depends on the attitude quaternion \(\mathbf{q}\) via the direction cosine matrix \(\mathbf{C}(\mathbf{q})\):

\[\mathbf{B}_{\mathcal{B}}(\mathbf{q}) = \mathbf{C}(\mathbf{q})^\top \mathbf{B}_{\mathrm{ECI}}.\]

The orbital-state provider Orbital_State supplies \(\mathbf{B}_{\mathcal{B}}\), its Jacobian \(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}\), and Hessian \(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}\) through get_state_vector().

param axis:

Unit vector defining the magnetorquer alignment in the body frame.

type axis:

numpy.ndarray

param max_torque:

Maximum allowable commanded dipole magnitude (used as the actuator saturation limit).

type max_torque:

float

param bias:

Bias model representing constant or slowly varying dipole offset.

type bias:

Bias | None

param noise:

Noise model representing stochastic actuation uncertainty.

type noise:

Noise | None

param estimate_bias:

If True, includes this actuator’s bias term in the estimator state vector.

type estimate_bias:

bool

ddtorq__dbasestatedbasestate(u, x, os)[source]

Base-state Hessian \(\partial^2\boldsymbol{\tau}/(\partial\mathbf{x}\,\partial\mathbf{x})\).

With the noise-free model

\[\boldsymbol{\tau}(u,\mathbf{q}) = -(\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a})\,(u+b),\]

all second derivatives involving \(\boldsymbol{\omega}\) vanish. The only nonzero block is the quaternion–quaternion block, using \(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q})\) ("ddb"):

\[\frac{\partial^2\boldsymbol{\tau}}{\partial\mathbf{q}\,\partial\mathbf{q}} = -\bigl(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr)\,(u+b).\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft base state.

  • os (Orbital_State) – Orbital state providing "ddb" via get_state_vector().

Returns:

Base-state Hessian tensor (only the quaternion block is nonzero).

Return type:

numpy.ndarray

ddtorq__dbiasdbasestate(u, x, os)[source]

Mixed second derivative \(\partial^2\boldsymbol{\tau}/(\partial b\,\partial\mathbf{x})\).

Since \(b\) enters identically to \(u\) in \((u+b)\), the mixed derivative equals the control–state mixed derivative:

\[\begin{split}\frac{\partial^2\boldsymbol{\tau}}{\partial b\,\partial\mathbf{x}} = \frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\mathbf{x}} = \begin{bmatrix} \mathbf{0}_{3\times 3}\\ -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr) \end{bmatrix}.\end{split}\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft base state.

  • os (Orbital_State) – Orbital state.

Returns:

Mixed Hessian tensor if a bias model exists; otherwise an empty tensor consistent with no bias state.

Return type:

numpy.ndarray

ddtorq__dbiasdbias(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}/\partial b^2\).

The bias \(b\) enters the torque linearly through \((u+b)\), so:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial b^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft base state.

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor if a bias model exists; otherwise an empty tensor consistent with no bias state.

Return type:

numpy.ndarray

ddtorq__dudbasestate(u, x, os)[source]

Mixed second derivative \(\partial^2\boldsymbol{\tau}/(\partial u\,\partial\mathbf{x})\).

With

\[\boldsymbol{\tau}(u,\mathbf{q}) = -(\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a})\,(u+b),\]

the mixed derivative is independent of \(u\) and has zero angular-velocity block:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\boldsymbol{\omega}} = \mathbf{0}_{1\times 3\times 3},\qquad \frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\mathbf{q}} = -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr).\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft base state.

  • os (Orbital_State) – Orbital state providing "db" via get_state_vector().

Returns:

Mixed Hessian tensor stacked by \((\boldsymbol{\omega},\mathbf{q})\) with a leading singleton control dimension.

Return type:

numpy.ndarray

ddtorq__dudh(u, x, os)[source]

Mixed second derivative \(\partial^2\boldsymbol{\tau}/(\partial u\,\partial\mathbf{h})\).

This actuator has no momentum-storage state \(\mathbf{h}\) in the model, so all derivatives w.r.t. \(\mathbf{h}\) are empty:

\[\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{h}}=\mathbf{0} \quad\Longrightarrow\quad \frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\mathbf{h}}=\mathbf{0}.\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft base state.

  • os (Orbital_State) – Orbital state.

Returns:

Empty tensor along the storage-state dimension (shape (1,0,3)).

Return type:

numpy.ndarray

dtorq__dbasestate(u, x, os)[source]

First derivative of torque with respect to the base spacecraft state.

The torque does not depend on angular velocity, and depends on attitude only through the magnetic field transformation.

Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray, shape (7,)) – Spacecraft state vector \([\boldsymbol{\omega};\mathbf{q}]\).

  • os (Orbital_State) – Orbital state providing magnetic field Jacobians.

Returns:

Jacobian of torque w.r.t. base state.

Return type:

numpy.ndarray, shape (7,3)

dtorq__du(u, x, os)[source]

First derivative of torque with respect to the control input.

\[\frac{\partial\boldsymbol{\tau}}{\partial u} = \mathbf{a} \times \mathbf{B}_{\mathcal{B}} = -\,\mathbf{B}_{\mathcal{B}} \times \mathbf{a}\]
Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray) – Spacecraft state vector.

  • os (Orbital_State) – Orbital state providing the body-frame magnetic field.

Returns:

Row Jacobian of torque w.r.t. control input.

Return type:

numpy.ndarray, shape (1,3)

hessians(u, x, os)[source]

Compute second-order derivatives (Hessians) of the torque.

Using the noise-free model

\[\boldsymbol{\tau}(u,\mathbf{q}) = -(\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a})\,(u+b),\]

and defining

  • \(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q})\in\mathbb{R}^{4\times 3}\) (provided as "db"),

  • \(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q})\in\mathbb{R}^{4\times 4\times 3}\) (provided as "ddb"),

the only nonzero second derivatives involve the quaternion.

Mixed control–state Hessian

The mixed derivative \(\partial^2\boldsymbol{\tau}/(\partial u\,\partial\mathbf{x})\) has zero angular-velocity block and a quaternion block:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\boldsymbol{\omega}} = \mathbf{0}_{1\times 3\times 3},\]
\[\frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\mathbf{q}} = -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr).\]

In stacked form (matching the base state \([\boldsymbol{\omega};\mathbf{q}]\)):

\[\begin{split}\frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial\mathbf{x}} = \begin{bmatrix} \mathbf{0}_{3\times 3}\\ -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr) \end{bmatrix}.\end{split}\]

Pure base-state Hessian

All second derivatives involving \(\boldsymbol{\omega}\) vanish, and the only nonzero block is the quaternion–quaternion block:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial\mathbf{q}\,\partial\mathbf{q}} = -\bigl(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr)\,(u+b).\]
param u:

Commanded magnetic dipole magnitude.

type u:

float

param x:

Spacecraft base state.

type x:

numpy.ndarray

param os:

Orbital state providing \(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}\) and \(D^2_{\mathbf{q}\mathbf{q}}\mathbf{B}_{\mathcal{B}}\) via get_state_vector().

type os:

Orbital_State

return:

(ddT_du_dx, ddT_dx2) where:

  • ddT_du_dx has shape (1,7,3) and equals \(\partial^2\boldsymbol{\tau}/(\partial u\,\partial\mathbf{x})\).

  • ddT_dx2 has shape (7,7,3) and equals \(\partial^2\boldsymbol{\tau}/(\partial\mathbf{x}\,\partial\mathbf{x})\).

rtype:

tuple[numpy.ndarray, numpy.ndarray]

Parameters:
Return type:

ndarray

jacobians(u, x, os)[source]

Compute first-order derivatives (Jacobians) of the torque.

Let \(\mathbf{a}=\texttt{self.axis}\) and let \(b\) be the (optional) scalar bias. The torque model (without noise) is

\[\boldsymbol{\tau}(u,\mathbf{q}) = -(\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a})\,(u+b).\]

Jacobian w.r.t. control input

Since \(\boldsymbol{\tau}\) is affine in \(u\):

\[\frac{\partial\boldsymbol{\tau}}{\partial u} = -(\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}).\]

Jacobian w.r.t. base state

The base state is \(\mathbf{x}=[\boldsymbol{\omega};\mathbf{q}]\in\mathbb{R}^7\). The torque depends on \(\mathbf{q}\) only through \(\mathbf{B}_{\mathcal{B}}(\mathbf{q})\) and does not depend on \(\boldsymbol{\omega}\):

\[\frac{\partial\boldsymbol{\tau}}{\partial\boldsymbol{\omega}} = \mathbf{0}_{3\times 3}.\]

With \(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q})\in\mathbb{R}^{4\times 3}\) (provided as "db"), the quaternion Jacobian is

\[\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{q}} = -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr)\,(u+b),\]

where the matrix–vector cross is applied row-wise: \(( \mathbf{M}\times\mathbf{v})_{i:}=\mathbf{M}_{i:}\times\mathbf{v}\).

The returned base-state Jacobian stacks these blocks as

\[\begin{split}\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{x}} = \begin{bmatrix} \mathbf{0}_{3\times 3}\\ -\bigl(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}(\mathbf{q}) \times \mathbf{a}\bigr)\,(u+b) \end{bmatrix}.\end{split}\]
param u:

Commanded magnetic dipole magnitude.

type u:

float

param x:

Spacecraft base state \([\boldsymbol{\omega};\mathbf{q}]\).

type x:

numpy.ndarray

param os:

Orbital state providing \(\mathbf{B}_{\mathcal{B}}\) and \(D_{\mathbf{q}}\mathbf{B}_{\mathcal{B}}\) via get_state_vector().

type os:

Orbital_State

return:

(dT_du, dT_dx) where:

  • dT_du has shape (1,3) and equals \(\partial\boldsymbol{\tau}/\partial u\).

  • dT_dx has shape (7,3) and equals \(\partial\boldsymbol{\tau}/\partial \mathbf{x}\).

rtype:

tuple[numpy.ndarray, numpy.ndarray]

Parameters:
Return type:

ndarray

storage_torque(u, x, os, dmode=None)[source]

Storage torque contribution of the actuator.

Magnetorquers do not store angular momentum. Consequently, this method always returns an empty vector.

Parameters:
  • u (float) – Commanded dipole magnitude.

  • x (numpy.ndarray) – Spacecraft state vector.

  • os (Orbital_State) – Orbital state.

  • dmode (ErrorMode | None) – Disturbance mode (unused).

Returns:

Empty storage-torque vector.

Return type:

numpy.ndarray, shape (0,)

torque(u, x, os, dmode=None)[source]

Compute the torque generated by the magnetorquer.

The applied body-frame torque is given by:

\[\boldsymbol{\tau} = -(\mathbf{B}_{\mathcal{B}} \times \mathbf{a})\,(u + b) + \mathbf{n}\]

where the magnetic field and its derivatives are obtained from Orbital_State.

Bias and noise terms are conditionally applied according to ErrorMode.

Parameters:
  • u (float) – Commanded magnetic dipole magnitude.

  • x (numpy.ndarray, shape (7,)) – Full spacecraft state vector \([\boldsymbol{\omega};\mathbf{q}]\).

  • os (Orbital_State | dict[str, numpy.ndarray]) – Orbital state providing geomagnetic field vectors and derivatives.

  • dmode (ErrorMode | None) – Disturbance mode specifying whether bias and noise are applied and/or updated.

Returns:

Body-frame torque vector.

Return type:

numpy.ndarray, shape (3,)

Parameters:
  • axis (ndarray)

  • max_torque (float)

  • bias (Bias)

  • noise (Noise)

  • estimate_bias (bool)