ADCS.satellite_hardware.actuators.reaction_wheel module

class ADCS.satellite_hardware.actuators.reaction_wheel.RW(axis, max_torque, J, h, h_max, bias=None, noise=None, h_meas_noise=None, estimate_bias=False)[source]

Bases: Actuator

Reaction Wheel (RW) Actuator Model

This class models a single-axis reaction wheel used for spacecraft attitude control. A reaction wheel generates a body torque by accelerating/decelerating its rotor, exchanging angular momentum with the spacecraft through conservation of angular momentum.

Torque model

Let \(\mathbf{a}\in\mathbb{R}^3\) be the wheel spin axis expressed in the spacecraft body frame, with \(\|\mathbf{a}\|=1\). Let \(u\) be the commanded motor torque (scalar) about the wheel axis.

The body torque applied by the wheel is

\[\boldsymbol{\tau}_{\mathrm{RW}} = \mathbf{a}\,u.\]

If actuator bias and noise are enabled, the effective commanded torque becomes

\[u_{\mathrm{eff}} = u + b(t) + n(t),\]

yielding

\[\boldsymbol{\tau}_{\mathrm{RW}} = \mathbf{a}\,\bigl(u + b(t) + n(t)\bigr).\]

Wheel momentum dynamics

Let \(\mathbf{h}\in\mathbb{R}^3\) denote the stored wheel angular momentum vector in the body frame. For a single-axis wheel, \(\mathbf{h}\) is collinear with \(\mathbf{a}\). By conservation of angular momentum, the internal wheel torque is equal and opposite to the body torque:

\[\boldsymbol{\tau}_{\mathrm{wheel}} = -\boldsymbol{\tau}_{\mathrm{RW}}.\]

Consequently, the wheel momentum changes according to

\[\dot{\mathbf{h}} = -\boldsymbol{\tau}_{\mathrm{RW}}.\]

The wheel momentum is limited by a saturation bound \(\|\mathbf{h}\|\le h_{\max}\) (componentwise in this implementation).

Measurement model

Wheel momentum measurements are modeled as

\[\tilde{\mathbf{h}} = \mathbf{h} + \nu_h,\]

where \(\nu_h\) is provided by Noise.

Related types

Parameters:
  • axis (ndarray)

  • max_torque (float)

  • J (float)

  • h (ndarray)

  • h_max (ndarray)

  • bias (Bias)

  • noise (Noise)

  • h_meas_noise (Noise)

  • estimate_bias (bool)

ddstor_torq__dbasestatedbasestate(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial \mathbf{x}_{\mathrm{base}}^2\).

The internal wheel torque is independent of the base state \(\mathbf{x}_{\mathrm{base}}\), so:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial \mathbf{x}_{\mathrm{base}}^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (7,7,1).

Return type:

numpy.ndarray

ddstor_torq__dbasestatedh(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial \mathbf{x}_{\mathrm{base}}\,\partial \mathbf{h}\).

The internal wheel torque does not depend on \(\mathbf{x}_{\mathrm{base}}\) nor \(\mathbf{h}\), hence:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial \mathbf{x}_{\mathrm{base}}\,\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (7,1,1).

Return type:

numpy.ndarray

ddstor_torq__dbiasdbasestate(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial b\,\partial \mathbf{x}_{\mathrm{base}}\).

The internal wheel torque is independent of the base state and linear in \(b\), hence:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial b\,\partial \mathbf{x}_{\mathrm{base}}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • 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

ddstor_torq__dbiasdbias(u, x, os)[source]

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

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

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial b^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • 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

ddstor_torq__dbiasdh(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial b\,\partial \mathbf{h}\).

The internal wheel torque does not depend on \(\mathbf{h}\), so:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial b\,\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • 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

ddstor_torq__dhdh(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial \mathbf{h}^2\).

The internal wheel torque is independent of the stored momentum \(\mathbf{h}\), so:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial \mathbf{h}^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,1,1).

Return type:

numpy.ndarray

ddstor_torq__dudbasestate(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u\,\partial \mathbf{x}_{\mathrm{base}}\).

The internal wheel torque does not depend on the base state \(\mathbf{x}_{\mathrm{base}}\), and is linear in \(u\). Therefore the mixed second derivative is zero:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial u\,\partial \mathbf{x}_{\mathrm{base}}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,7,1).

Return type:

numpy.ndarray

ddstor_torq__dudbias(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u\,\partial b\).

The bias \(b\) enters linearly through \((u+b)\), so the mixed second derivative is zero:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial u\,\partial b} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • 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

ddstor_torq__dudh(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u\,\partial \mathbf{h}\).

The internal wheel torque does not depend on \(\mathbf{h}\), hence:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial u\,\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,1,1).

Return type:

numpy.ndarray

ddstor_torq__dudu(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u^2\).

The internal wheel torque depends linearly on \(u\):

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

so its second derivative with respect to \(u\) is zero:

\[\frac{\partial^2\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial u^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,1,1).

Return type:

numpy.ndarray

ddtorq__dbasestatedh(u, x, os)[source]

Second derivative \(\partial^2\boldsymbol{\tau}/\partial \mathbf{x}_{\mathrm{base}}\,\partial \mathbf{h}\).

The torque model \(\boldsymbol{\tau}=\mathbf{a}\,u_{\mathrm{eff}}\) does not depend on the spacecraft base state \(\mathbf{x}_{\mathrm{base}}\) nor on \(\mathbf{h}\). Therefore the mixed second derivative is identically zero:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial \mathbf{x}_{\mathrm{base}}\,\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (7,1,3).

Return type:

numpy.ndarray

ddtorq__dbiasdh(u, x, os)[source]

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

The torque does not depend on \(\mathbf{h}\), so the mixed derivative with respect to bias and momentum is zero:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial b\,\partial \mathbf{h}} = \mathbf{0}.\]

If a bias model exists, the returned tensor is the appropriately shaped zero tensor. If no bias model exists, an empty tensor consistent with the absence of bias states is returned.

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • 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__dhdh(u, x, os)[source]

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

The torque does not depend on the stored wheel momentum \(\mathbf{h}\), so:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial \mathbf{h}^2} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,1,3).

Return type:

numpy.ndarray

ddtorq__dudh(u, x, os)[source]

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

The torque does not depend on \(\mathbf{h}\), so the mixed second derivative is identically zero:

\[\frac{\partial^2\boldsymbol{\tau}}{\partial u\,\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero tensor, shape (1,1,3).

Return type:

numpy.ndarray

dstor_torq__dbasestate(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}_{\mathrm{wheel}}/\partial \mathbf{x}_{\mathrm{base}}\).

The internal wheel torque depends only on the commanded torque (and optional bias/noise), not on the spacecraft base state \(\mathbf{x}_{\mathrm{base}}\). Hence,

\[\frac{\partial\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial \mathbf{x}_{\mathrm{base}}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero Jacobian, shape (7,1).

Return type:

numpy.ndarray

dstor_torq__dbias(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}_{\mathrm{wheel}}/\partial b\).

The bias \(b\) enters the effective command linearly through \(u_{\mathrm{eff}} = u + b + n\), and the internal wheel torque is \(\boldsymbol{\tau}_{\mathrm{wheel}} = -\mathbf{a}\,u_{\mathrm{eff}}\). Therefore,

\[\frac{\partial\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial b} = -\mathbf{a}.\]

In this implementation, the storage torque is represented in scalar form, so the derivative is -1 when a bias state exists; otherwise an empty tensor consistent with no bias state is returned.

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

(1,1) matrix equal to \(-1\) if a bias model exists; otherwise an empty array with shape (0,1).

Return type:

numpy.ndarray

dstor_torq__dh(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}_{\mathrm{wheel}}/\partial \mathbf{h}\).

The internal wheel torque does not depend on the stored momentum \(\mathbf{h}\) in this actuator model, so:

\[\frac{\partial\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero Jacobian, shape (1,1).

Return type:

numpy.ndarray

dstor_torq__du(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u\).

The internal wheel torque is

\[\boldsymbol{\tau}_{\mathrm{wheel}} = -\mathbf{a}\,u_{\mathrm{eff}}, \qquad u_{\mathrm{eff}} = u + b(t) + n(t).\]

Differentiating with respect to \(u\) yields

\[\frac{\partial\boldsymbol{\tau}_{\mathrm{wheel}}}{\partial u} = -\mathbf{a}.\]

In this implementation, the storage torque is returned as a scalar command-like quantity, so the Jacobian with respect to the scalar input is a (1,1) matrix equal to \(-1\).

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Jacobian \(\partial\boldsymbol{\tau}_{\mathrm{wheel}}/\partial u\), shape (1,1).

Return type:

numpy.ndarray

dtorq__dh(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}/\partial \mathbf{h}\).

In this model, the applied body torque \(\boldsymbol{\tau}\) depends on the commanded torque and (optionally) actuator bias/noise, but not on the stored wheel momentum state \(\mathbf{h}\). Hence,

\[\frac{\partial\boldsymbol{\tau}}{\partial \mathbf{h}} = \mathbf{0}.\]
Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Zero Jacobian \(\partial\boldsymbol{\tau}/\partial \mathbf{h}\), shape (1,3).

Return type:

numpy.ndarray

dtorq__du(u, x, os)[source]

Jacobian \(\partial\boldsymbol{\tau}/\partial u\).

The body torque is

\[\boldsymbol{\tau}(u) = \mathbf{a}\,u_{\mathrm{eff}}, \qquad u_{\mathrm{eff}} = u + b(t) + n(t),\]

and the mapping from scalar command \(u\) to torque is linear. Therefore,

\[\frac{\partial\boldsymbol{\tau}}{\partial u} = \mathbf{a}.\]

This implementation returns a row-shaped Jacobian consistent with a scalar input and a 3D torque output.

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

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

  • os (Orbital_State) – Orbital state.

Returns:

Jacobian \(\partial\boldsymbol{\tau}/\partial u\), shape (1,3).

Return type:

numpy.ndarray

measure_momentum()[source]

Measure the wheel angular momentum with additive measurement noise.

The measurement model is

\[\tilde{\mathbf{h}} = \mathbf{h} + \nu_h,\]

where \(\nu_h\) is sampled from h_meas_noise, an instance of Noise.

Returns:

Noisy wheel momentum measurement \(\tilde{\mathbf{h}}\) [N·m·s], shape (3,).

Return type:

numpy.ndarray

measure_momentum_noiseless()[source]

Measure the wheel angular momentum without measurement noise.

This returns the stored wheel momentum state directly:

\[\tilde{\mathbf{h}} = \mathbf{h}.\]
Returns:

Noiseless wheel momentum \(\mathbf{h}\) [N·m·s], shape (3,).

Return type:

numpy.ndarray

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

Compute the internal torque acting on the wheel (equal and opposite to the body torque).

The wheel experiences the opposite torque to that applied to the spacecraft body. Using the same effective scalar command \(u_{\mathrm{eff}} = u + b(t) + n(t)\) (when enabled), the internal wheel torque is

\[\boldsymbol{\tau}_{\mathrm{wheel}} = -\boldsymbol{\tau}_{\mathrm{RW}} = -\mathbf{a}\,u_{\mathrm{eff}}.\]

This quantity is the torque that drives the wheel momentum dynamics:

\[\dot{\mathbf{h}} = \boldsymbol{\tau}_{\mathrm{wheel}}.\]

If \(|u| > u_{\max}\) a warning is emitted; the returned value is not clipped.

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • x (numpy.ndarray) – Spacecraft state vector (passed through for interface compatibility).

  • os (Orbital_State) – Orbital state providing time tag (e.g., J2000) for bias evolution.

  • dmode (ErrorMode | None) – Disturbance mode toggles controlling inclusion and update of bias and noise.

Returns:

Internal wheel torque vector \(\boldsymbol{\tau}_{\mathrm{wheel}}\) [N·m], shape (3,).

Return type:

numpy.ndarray

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

Compute the reaction-wheel torque vector applied to the spacecraft body.

The commanded scalar motor torque \(u\) is mapped onto the wheel axis \(\mathbf{a}\) to produce a 3D body torque. If enabled via ErrorMode, additive bias \(b(t)\) and noise \(n(t)\) are applied to the scalar torque before mapping.

\[u_{\mathrm{eff}} = u + b(t) + n(t),\]
\[\boldsymbol{\tau}_{\mathrm{RW}} = \mathbf{a}\,u_{\mathrm{eff}}.\]

Bias evolution (if present) may depend on the orbital time tag \(t\), provided here through J2000.

If \(|u| > u_{\max}\) a warning is emitted; the returned torque is not clipped.

Parameters:
  • u (float) – Commanded motor torque about the wheel axis [N·m].

  • x (numpy.ndarray) – Spacecraft state vector (passed through for interface compatibility).

  • os (Orbital_State) – Orbital state providing time tag (e.g., J2000) for bias evolution.

  • dmode (ErrorMode | None) – Disturbance mode toggles controlling inclusion and update of bias and noise.

Returns:

Body torque vector \(\boldsymbol{\tau}_{\mathrm{RW}}\) [N·m], shape (3,).

Return type:

numpy.ndarray

update_momentum(h)[source]

Update the stored wheel angular momentum.

This method overwrites the internal momentum state \(\mathbf{h}\). If the provided value exceeds the saturation bound, a warning is emitted; the value is still assigned.

\[\mathbf{h} \leftarrow \mathbf{h}_{\text{new}}.\]
Parameters:

h (float) – New wheel angular momentum [N·m·s].

Returns:

None.

Return type:

NoneType