ADCS.satellite_hardware.satellite.satellite module¶
- class ADCS.satellite_hardware.satellite.satellite.Satellite(mass=1.0, COM=None, J_0=None, disturbances=[], sensors=[], actuators=[], boresight=None)[source]¶
Bases:
objectRigid-body spacecraft model with sensors, actuators, and environmental disturbances.
This class bundles the spacecraft physical properties (mass, center of mass, inertia), a set of actuators (e.g.,
RW,MTQ), sensors (e.g.,Gyro,MTM,SunSensor,GPS), and disturbance models (e.g.,SRP_Disturbance).The rotational state is represented by body angular velocity and a unit quaternion. Reaction wheel angular momentum states may be appended.
State definition
Let the full state be
\[\begin{split}\mathbf{x} \;=\; \begin{bmatrix} \boldsymbol{\omega} \\ \mathbf{q} \\ \mathbf{h}_{\mathrm{RW}} \end{bmatrix} \in \mathbb{R}^{7+n_{\mathrm{RW}}},\end{split}\]where
\(\boldsymbol{\omega}\in\mathbb{R}^3\) is the body angular velocity (rad/s),
\(\mathbf{q}\in\mathbb{R}^4\) is a unit quaternion (Hamilton convention, body→ECI),
\(\mathbf{h}_{\mathrm{RW}}\in\mathbb{R}^{n_{\mathrm{RW}}}\) are wheel momenta.
Kinematics
Quaternion kinematics are
\[\dot{\mathbf{q}} = \frac{1}{2}\,\Omega(\boldsymbol{\omega})\,\mathbf{q},\]with an equivalent matrix form implemented via
Wmat().Dynamics (bus + wheels)
Define the total external torque
\[\boldsymbol{\tau} \;=\; \boldsymbol{\tau}_{\mathrm{dist}}(\mathbf{x}, \mathrm{os}) \;+\; \boldsymbol{\tau}_{\mathrm{act}}(\mathbf{x}, \mathbf{u}, \mathrm{os}).\]The rigid-body rotational equation is
\[\mathbf{J}\,\dot{\boldsymbol{\omega}} \;=\; -\boldsymbol{\omega}\times\Big(\mathbf{J}\boldsymbol{\omega} + \mathbf{H}_{\mathrm{RW}}\Big) \;+\; \boldsymbol{\tau},\]where \(\mathbf{H}_{\mathrm{RW}}\) is the body-frame contribution of stored wheel momentum. When wheels exist, wheel momentum dynamics follow actuator storage torques and the coupling term induced by \(\dot{\boldsymbol{\omega}}\).
Frames and environment
Environmental vectors are provided by
Orbital_Stateand rotated into the body frame viarot_mat().Inertia shifting
The inertia tensor about the center of mass is computed using the parallel axis theorem:
\[\mathbf{J}_{\mathrm{COM}} \;=\; \mathbf{J}_0 \;-\; m\left(\|\mathbf{r}_{\mathrm{COM}}\|^2\mathbf{I} \;-\;\mathbf{r}_{\mathrm{COM}}\mathbf{r}_{\mathrm{COM}}^\top\right),\]where \(\mathbf{J}_0\) is the inertia about the reference origin and \(\mathbf{r}_{\mathrm{COM}}\) is the COM offset in the same frame.
Note
Many methods accept an
ErrorModeto control bias/noise injection for Monte-Carlo simulation vs. deterministic propagation.Stored attributes (selected)
Attribute
Meaning
massTotal mass (kg)
COMCenter of mass vector (m)
J_0Inertia about reference (kg·m²)
J_COMInertia about COM (kg·m²)
J_noRWBus inertia excluding wheels
state_len7 + number_RWcontrol_lenlen(actuators)- Raises:
ValueError – If
COMis not shape(3,)orJ_0is not shape(3,3).- Parameters:
mass (float)
COM (ndarray)
J_0 (ndarray)
disturbances (List[Disturbance])
sensors (List[Sensor])
actuators (List[Actuator])
boresight (dict[str, ndarray] | ndarray)
- GPS_readings(x, os)[source]¶
Return GPS sensor readings.
GPS sensors are identified as instances of
GPS.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
List of GPS reading arrays (model-specific shapes).
- Return type:
list[numpy.ndarray]
- RW_readings(x, os)[source]¶
Return reaction wheel momentum measurements (with wheel measurement model behavior).
Delegates to each wheel’s
measure_momentum().- Parameters:
x (numpy.ndarray) – Current state vector (unused by some wheel models but included for interface consistency).
os (
Orbital_State) – Orbital/environmental state (unused by some wheel models but included for interface consistency).
- Returns:
List of per-wheel measurement arrays.
- Return type:
list[numpy.ndarray]
- RWhs()[source]¶
Return the current reaction wheel momenta as a vector.
The returned vector is ordered according to
self.momentum_inds(indices ofRWwithinself.actuators).- Returns:
Reaction wheel momentum vector, shape
(number_RW,).- Return type:
numpy.ndarray
- RWhs_from_state(state)[source]¶
Extract the reaction wheel momenta subvector from a full state vector.
Using the state layout
\[\mathbf{x} = \begin{bmatrix} \boldsymbol{\omega} & \mathbf{q} & \mathbf{h}_{RW} \end{bmatrix}^\top,\]this returns \(\mathbf{h}_{RW} = \mathbf{x}[7:]\).
- Parameters:
state (numpy.ndarray) – Full state vector, shape
(state_len,).- Returns:
Reaction wheel momentum vector, shape
(number_RW,).- Return type:
numpy.ndarray
- act_torque(x, u, os, dmode=None)[source]¶
Compute the total actuator torque.
The total actuator torque is
\[\boldsymbol{\tau}_{act}(\mathbf{x},\mathbf{u},\mathrm{os}) \;=\;\sum_{j=1}^{N_u} \boldsymbol{\tau}_{act,j}(u_j,\mathbf{x},\mathrm{os}),\]where each actuator is a subclass of
Actuator.- Parameters:
x (numpy.ndarray) – State vector, shape
(state_len,).u (numpy.ndarray) – Control input vector, shape
(control_len,).os (
Orbital_State) – Orbital/environmental state.dmode (
ErrorMode| None) – Error/noise mode passed to actuator torque models.
- Returns:
Actuator torque vector in body frame, shape
(3,)(N·m).- Return type:
numpy.ndarray
- dist_torque_hess(x, vecs)[source]¶
Hessian tensors of total disturbance torque.
Returns second derivatives of \(\boldsymbol{\tau}_{dist}\):
\[\frac{\partial^2 \boldsymbol{\tau}_{dist}}{\partial \mathbf{x}^2}, \qquad \frac{\partial^2 \boldsymbol{\tau}_{dist}}{\partial \mathbf{x}\,\partial \boldsymbol{\theta}_d}, \qquad \frac{\partial^2 \boldsymbol{\tau}_{dist}}{\partial \boldsymbol{\theta}_d^2}.\]As with
dist_torques_jacobian(), only quaternion components contribute in the current formulation, and each disturbance must implement:torque_qqhess(self, vecs)→ \(\partial^2 \boldsymbol{\tau}/\partial \mathbf{q}^2\).
- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).vecs (dict[str, numpy.ndarray]) – Dictionary of body-frame environment vectors and their first/second quaternion derivatives.
- Returns:
Triple
(dddist_torq__dxdx, dddist_torq__dxddmp, dddist_torq__ddmpddmp).- Return type:
tuple[numpy.ndarray, numpy.ndarray, numpy.ndarray]
Return shapes
Name
Shape
dddist_torq__dxdx(state_len, state_len, 3)dddist_torq__dxddmp(state_len, dist_param_len, 3)dddist_torq__ddmpddmp(dist_param_len, dist_param_len, 3)
- dist_torques(x, os, dmode=None)[source]¶
Compute the total disturbance torque.
The total disturbance torque is the sum over all registered disturbances:
\[\boldsymbol{\tau}_{dist}(\mathbf{x},\mathrm{os}) \;=\;\sum_{i=1}^{N_d} \boldsymbol{\tau}_{dist,i}(\mathbf{x},\mathrm{os}).\]Disturbance implementations may optionally accept a
satkeyword argument; if so, the currentSatelliteinstance is provided.- Parameters:
x (numpy.ndarray) – State vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.dmode (
ErrorMode| None) – Optional error/noise mode (typically used inside disturbances if supported).
- Returns:
Disturbance torque vector in body frame, shape
(3,)(N·m).- Return type:
numpy.ndarray
- dist_torques_jacobian(x, vecs)[source]¶
Jacobians of total disturbance torque with respect to the state and disturbance parameters.
Let \(\boldsymbol{\tau}_{dist}(\mathbf{x})\) be the total disturbance torque. This method returns:
\[\frac{\partial \boldsymbol{\tau}_{dist}}{\partial \mathbf{x}} \in \mathbb{R}^{n_x\times 3}, \qquad \frac{\partial \boldsymbol{\tau}_{dist}}{\partial \boldsymbol{\theta}_d} \in \mathbb{R}^{n_{\theta_d}\times 3}.\]In the provided implementation, only the quaternion components affect the disturbance torque Jacobian, because environment vectors are rotated by attitude. Thus, the nonzero block is
\[\left[\frac{\partial \boldsymbol{\tau}_{dist}}{\partial \mathbf{x}}\right]_{3:7,:} = \sum_i \frac{\partial \boldsymbol{\tau}_{dist,i}}{\partial \mathbf{q}}.\]Each disturbance model must implement:
torque_qjac(self, vecs)→ \(\partial \boldsymbol{\tau}/\partial \mathbf{q}\).
- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).vecs (dict[str, numpy.ndarray]) – Dictionary of body-frame environment vectors and their quaternion derivatives, e.g.
{"b","r","s","v","rho","db","dr","ds","dv","os"}.
- Returns:
Pair
(ddist_torq__dx, ddist_torq__ddmp).- Return type:
tuple[numpy.ndarray, numpy.ndarray]
Return shapes
Name
Shape
ddist_torq__dx(state_len, 3)ddist_torq__ddmp(dist_param_len, 3)
- dynJacCore(x, u, orbital_state)[source]¶
Compute Jacobians of the dynamics with respect to state and input.
This method returns the first-order linearization
\[\delta \dot{\mathbf{x}} \approx \mathbf{A}\,\delta\mathbf{x} + \mathbf{B}\,\delta\mathbf{u},\]where
\[\mathbf{A} = \frac{\partial f}{\partial \mathbf{x}},\qquad \mathbf{B} = \frac{\partial f}{\partial \mathbf{u}}.\]Environmental vectors (magnetic field, sun vector, velocity, position) are rotated into the body frame:
\[\mathbf{v}_B(\mathbf{q}) = R(\mathbf{q})^\top \mathbf{v}_{ECI},\]and derivatives \(\partial \mathbf{v}_B/\partial \mathbf{q}\) are obtained via
drotmatTvecdq().Actuator torque derivatives are aggregated via each actuator’s methods, e.g.
dtorq__dbasestateanddtorq__du; disturbance derivatives are aggregated viadist_torques_jacobian().- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).u (numpy.ndarray) – Current control vector, shape
(control_len,).orbital_state (
Orbital_State) – Orbital/environmental state.
- Returns:
List
[dxdot__dx, dxdot__du].- Return type:
list[numpy.ndarray]
Return shapes
Name
Shape
dxdot__dx(state_len, state_len)dxdot__du(control_len, state_len)
- dynamics_Hessians(x, u, orbital_state)[source]¶
Compute second-order partial derivatives (Hessians) of the dynamics.
Returns the second derivatives of the dynamics map \(\dot{\mathbf{x}} = f(\mathbf{x},\mathbf{u},\mathrm{os})\) with respect to state and input:
\[\frac{\partial^2 f}{\partial \mathbf{x}^2}, \qquad \frac{\partial^2 f}{\partial \mathbf{x}\partial \mathbf{u}}, \qquad \frac{\partial^2 f}{\partial \mathbf{u}^2}.\]These are useful for second-order trajectory optimization methods (DDP/iLQR) and nonlinear uncertainty propagation.
Frame rotation derivatives
Environmental vectors are rotated into body frame and their first and second derivatives with respect to the quaternion are computed:
\[\mathbf{v}_B(\mathbf{q}) = R(\mathbf{q})^\top \mathbf{v}_{ECI},\quad \frac{\partial \mathbf{v}_B}{\partial \mathbf{q}},\quad \frac{\partial^2 \mathbf{v}_B}{\partial \mathbf{q}^2},\]using
drotmatTvecdq()andddrotmatTvecdqdq().Output structure
The return is a nested list representing the block Hessians:
[ [ ddxdot__dxdx, ddxdot__dxdu ], [ ddxdot__dxdu.T, ddxdot__dudu ] ]
where the final tensor index selects the component of \(\dot{\mathbf{x}}\).
- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).u (numpy.ndarray) – Current control vector, shape
(control_len,).orbital_state (
Orbital_State) – Orbital/environmental state.
- Returns:
Nested list of Hessian tensors
[[ddxdot__dxdx, ddxdot__dxdu],[ddxdot__dxdu.T, ddxdot__dudu]].- Return type:
list[list[numpy.ndarray]]
Return shapes
Name
Shape
ddxdot__dxdx(state_len, state_len, state_len)ddxdot__dxdu(state_len, control_len, state_len)ddxdot__dudu(control_len, control_len, state_len)
- dynamics_core(x, u, orbital_state, dmode=None, verbose=False)[source]¶
Continuous-time attitude dynamics \(\dot{\mathbf{x}} = f(\mathbf{x},\mathbf{u},\mathrm{os})\).
This is the primary nonlinear dynamics model used by propagation, simulation, and linearization routines.
Kinematics
Quaternion kinematics are computed as
\[\dot{\mathbf{q}} \;=\;\frac{1}{2}\,W(\mathbf{q})^\top\,\boldsymbol{\omega},\]where \(W(\mathbf{q})\) is produced by
Wmat().Torques
Disturbance and actuator torques are summed:
\[\boldsymbol{\tau}_{dist} = \sum_i \boldsymbol{\tau}_{dist,i}(\mathbf{x},\mathrm{os}), \qquad \boldsymbol{\tau}_{act} = \sum_j \boldsymbol{\tau}_{act,j}(\mathbf{x},\mathbf{u},\mathrm{os}),\]using
dist_torques()andact_torque().Rigid-body dynamics
If no reaction wheels are present:
\[\dot{\boldsymbol{\omega}} \;=\;\mathbf{J}_{noRW}^{-1}\Big( -\boldsymbol{\omega}\times(\mathbf{J}\boldsymbol{\omega}) + \boldsymbol{\tau} \Big).\]If reaction wheels are present, let \(\mathbf{A}\in\mathbb{R}^{n_{RW}\times 3}\) stack wheel spin axes as rows, and let \(\mathbf{h}\in\mathbb{R}^{n_{RW}}\) be wheel momenta. Then the coupled term uses the body-frame stored momentum \(\mathbf{H}_{RW} = \mathbf{h}^\top \mathbf{A}\) and
\[\dot{\boldsymbol{\omega}} \;=\;\mathbf{J}_{noRW}^{-1}\Big( -\boldsymbol{\omega}\times(\mathbf{J}\boldsymbol{\omega} + \mathbf{H}_{RW}) + \boldsymbol{\tau} \Big).\]Wheel momentum dynamics use the actuator storage torque commands (from each
RW) and subtract the coupling term from body acceleration:\[\dot{\mathbf{h}} \;=\;\mathbf{u}_{RW} \;-\; \mathbf{A}\,\dot{\boldsymbol{\omega}}\,\mathrm{diag}(J_{RW}),\]matching the implementation structure.
- Parameters:
x (numpy.ndarray) – State vector
[w(3), q(4), h(number_RW)], shape(state_len,).u (numpy.ndarray) – Control vector, one element per actuator, shape
(control_len,).orbital_state (
Orbital_State) – Orbital/environmental state providing vectors (e.g. magnetic field), used by torques.dmode (
ErrorMode| None) – Error/noise/bias mode used by sensors/actuators/disturbances. IfNone, a default with bias+noise enabled and updated is used.verbose (bool) – If
True, prints a detailed torque and derivative breakdown.
- Returns:
Time derivative vector \(\dot{\mathbf{x}}\), shape
(state_len,).- Return type:
numpy.ndarray
- dynamics_for_solver(t, x, u, os0, os1)[source]¶
Wrapper for ODE solvers expecting signature
f(t, x).This method interpolates the orbital/environmental state between
os0andos1using the fraction of elapsed time\[\alpha = \frac{t}{\Delta t},\qquad \Delta t = (J2000_1 - J2000_0)\cdot C_{\mathrm{cent}\to \mathrm{sec}},\]and calls
dynamics_core()with anErrorModethat does not update bias/noise so the solver uses a consistent noise sample.- Parameters:
t (float) – Time since start of the interval (s).
x (numpy.ndarray) – Current state vector, shape
(state_len,).u (numpy.ndarray) – Constant (or externally provided) control input for the interval, shape
(control_len,).os0 (
Orbital_State) – Orbital state at the interval start.os1 (
Orbital_State) – Orbital state at the interval end.
- Returns:
State derivative \(\dot{\mathbf{x}}\), shape
(state_len,).- Return type:
numpy.ndarray
- gen_dist_off(ind=None)[source]¶
Turn off general disturbances.
General disturbances correspond to
General_Disturbance.- Parameters:
ind (int | None) – Optional index to toggle only one disturbance instance.
- Returns:
None.- Return type:
None
- gen_dist_on(ind=None)[source]¶
Turn on general disturbances.
General disturbances correspond to
General_Disturbance.- Parameters:
ind (int | None) – Optional index to toggle only one disturbance instance.
- Returns:
None.- Return type:
None
- gyro_readings(x, os)[source]¶
Return readings from all gyroscopes.
Filters
self.attitude_sensorsbyGyroand returnssensor.reading(x, os)for each.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
List of gyro measurement arrays (typically angular rate, rad/s).
- Return type:
list[numpy.ndarray]
- mtm_readings(x, os)[source]¶
Return readings from all magnetometers.
Filters
self.attitude_sensorsbyMTM.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
List of magnetometer measurement arrays (typically magnetic field, T).
- Return type:
list[numpy.ndarray]
- noiseless_RW_readings(x, os)[source]¶
Return noiseless reaction wheel momentum measurements.
Delegates to each wheel’s
measure_momentum_noiseless()(implementation-specific).- Parameters:
x (numpy.ndarray) – Current state vector (unused by some wheel models but included for interface consistency).
os (
Orbital_State) – Orbital/environmental state (unused by some wheel models but included for interface consistency).
- Returns:
List of per-wheel measurement arrays.
- Return type:
list[numpy.ndarray]
- noiseless_rk4(x, u, dt, orbital_state0, orbital_state1, verbose=False, mid_orbital_state=None, quat_as_vec=True, give_err_est=False)[source]¶
Propagate the state forward one step using RK4 (and optional embedded error estimate).
Quaternion components are normalized at each substep to avoid drift.
RK4 update
\[\begin{split}\begin{aligned} \mathbf{k}_1 &= f(\mathbf{x}_n,\mathbf{u},\mathrm{os}_0) \\ \mathbf{k}_2 &= f(\mathbf{x}_n+\tfrac{dt}{2}\mathbf{k}_1,\mathbf{u},\mathrm{os}_{1/2}) \\ \mathbf{k}_3 &= f(\mathbf{x}_n+\tfrac{dt}{2}\mathbf{k}_2,\mathbf{u},\mathrm{os}_{1/2}) \\ \mathbf{k}_4 &= f(\mathbf{x}_n+dt\,\mathbf{k}_3,\mathbf{u},\mathrm{os}_1) \\ \mathbf{x}_{n+1} &= \mathbf{x}_n + \tfrac{dt}{6}\left(\mathbf{k}_1 + 2\mathbf{k}_2 + 2\mathbf{k}_3 + \mathbf{k}_4\right) \end{aligned}\end{split}\]where \(\mathrm{os}_{1/2}\) is the midpoint orbital state; if not provided it is computed via
average().Embedded error estimate (optional)
When
give_err_est=True, a third-order embedded estimate \(\mathbf{x}^{(3)}_{n+1}\) is computed, and the elementwise difference is returned as a local truncation error proxy.Noise/bias behavior
This routine enforces a deterministic propagation by using an
ErrorModewith all noise/bias additions disabled.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).u (numpy.ndarray) – Control vector, shape
(control_len,).dt (float) – Integration time step (s).
orbital_state0 (
Orbital_State) – Orbital state at the start of the step.orbital_state1 (
Orbital_State) – Orbital state at the end of the step.verbose (bool) – If
True, prints intermediate RK stages.mid_orbital_state (
Orbital_State| None) – Optional precomputed midpoint orbital state.quat_as_vec (bool) – If
True, propagate quaternions using RK4 on the quaternion components with normalization. IfFalse, use a commutator-free Lie group method (CG5) for quaternion propagation.give_err_est (bool) – If
True, return(x_next, err_est)using an embedded lower-order estimate.
- Returns:
Next state, or
(next_state, error_estimate)ifgive_err_est=True.- Return type:
numpy.ndarray | tuple[numpy.ndarray, numpy.ndarray]
- Raises:
ValueError – If
give_err_est=Truewhile using the CG5 quaternion propagation variant.
- noiseless_sensor_readings(x, os)[source]¶
Compute sensor readings with noise disabled (bias may be included but not updated).
Uses an
ErrorModeconfigured as:add_bias = True
add_noise = False
update_bias = False
update_noise = False
This is useful for deterministic filtering tests where bias is treated as a fixed offset.
- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
Concatenated measurement vector.
- Return type:
numpy.ndarray
- prop_dist_off(ind=None)[source]¶
Turn off propulsion disturbances.
Propulsion disturbances correspond to
Prop_Disturbance.- Parameters:
ind (int | None) – Optional index to toggle only one disturbance instance.
- Returns:
None.- Return type:
None
- prop_dist_on(ind=None)[source]¶
Turn on propulsion disturbances.
Propulsion disturbances correspond to
Prop_Disturbance.- Parameters:
ind (int | None) – Optional index to toggle only one disturbance instance.
- Returns:
None.- Return type:
None
- sensor_readings(x, os, dmode=None)[source]¶
Compute concatenated sensor readings (attitude sensors + wheel momentum measurements).
Readings are collected from all non-GPS sensors in
self.attitude_sensorsand appended with reaction wheel momentum measurements from eachRW.Let \(\mathbf{y}\) denote the stacked measurement vector:
\[\begin{split}\mathbf{y} = \begin{bmatrix} \mathbf{y}_1 \\ \vdots \\ \mathbf{y}_{N_s} \\ \hat{\mathbf{h}}_{RW} \end{bmatrix},\end{split}\]where each \(\mathbf{y}_i\) is a sensor-specific output (possibly vector-valued).
- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.dmode (
ErrorMode| None) – Error/noise mode controlling sensor noise/bias injection.
- Returns:
Concatenated measurement vector.
- Return type:
numpy.ndarray
- specific_dist_off(ind)[source]¶
Turn off a specific disturbance model by index.
- Parameters:
ind (int) – Index into
self.disturbances.- Returns:
None.- Return type:
None
- Raises:
IndexError – If
indis out of range.
- specific_dist_on(ind)[source]¶
Turn on a specific disturbance model by index.
- Parameters:
ind (int) – Index into
self.disturbances.- Returns:
None.- Return type:
None
- Raises:
IndexError – If
indis out of range.
- srp_dist_off()[source]¶
Turn off all Solar Radiation Pressure disturbances.
Equivalent to calling:
self._toggle_disturbance(SRP_Disturbance, on=False)
- Returns:
None.- Return type:
None
- srp_dist_on()[source]¶
Turn on all Solar Radiation Pressure disturbances.
Equivalent to calling:
self._toggle_disturbance(SRP_Disturbance, on=True)
- Returns:
None.- Return type:
None
- sunpair_readings(x, os)[source]¶
Return readings from all sun-pair sensors.
Filters
self.attitude_sensorsbySunPair.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
List of sun-pair measurement arrays (model-specific shapes).
- Return type:
list[numpy.ndarray]
- sunsensor_readings(x, os)[source]¶
Return readings from all sun sensors.
Filters
self.attitude_sensorsbySunSensor.- Parameters:
x (numpy.ndarray) – Current state vector, shape
(state_len,).os (
Orbital_State) – Orbital/environmental state.
- Returns:
List of sun sensor measurement arrays (model-specific shapes).
- Return type:
list[numpy.ndarray]
- update_J(J_0=None, COM=None)[source]¶
Update inertia matrices and cached inverses.
This method validates the inertia tensor, enforces symmetry, checks positive definiteness, shifts the inertia to the center of mass, and computes additional derived inertias.
Validation
The inertia is required to be real, symmetric, and positive definite:
\[\mathbf{J} = \mathbf{J}^\top,\qquad \lambda_i(\mathbf{J})>0.\]Parallel axis theorem
If \(\mathbf{J}_0\) is about the reference origin and \(\mathbf{r}_{COM}\) is the COM offset, then
\[\mathbf{J}_{COM} \;=\; \mathbf{J}_0 \;-\; m\left(\|\mathbf{r}_{COM}\|^2\mathbf{I} - \mathbf{r}_{COM}\mathbf{r}_{COM}^\top\right).\]Excluding reaction wheel inertia
If wheels are present, the bus-only inertia is approximated by subtracting wheel spin-axis contributions:
\[\mathbf{J}_{noRW} \;=\; \mathbf{J}_{COM} \;-\; \sum_{k=1}^{n_{RW}} J_{RW,k}\,\hat{\mathbf{a}}_k \hat{\mathbf{a}}_k^\top,\]where \(J_{RW,k}\) and \(\hat{\mathbf{a}}_k\) are the wheel rotor inertia and spin axis.
Cached inverses are computed for efficient dynamics evaluation.
- Parameters:
J_0 (numpy.ndarray | None) – Inertia tensor about the reference origin, shape
(3,3). IfNone, usesself.J_0.COM (numpy.ndarray | None) – Center of mass offset, shape
(3,). IfNone, usesself.COM.
- Returns:
None.- Return type:
None
- Raises:
ValueError – If
J_0cannot be reshaped to(3,3), contains non-real values, is not symmetric within tolerance, or is not positive definite.
- update_RWhs(state_or_RWhs)[source]¶
Update stored wheel momentum values in each
RW.If
state_or_RWhshas lengthself.state_len, it is interpreted as the full state \(\mathbf{x}\) and wheel momenta are extracted viaRWhs_from_state(). Otherwise, it is interpreted as the wheel momentum vector directly.- Parameters:
state_or_RWhs (numpy.ndarray) – Either full state vector (shape
(state_len,)) or wheel momenta (shape(number_RW,)).- Returns:
None.- Return type:
None
- Raises:
ValueError – If the inferred wheel momentum vector length does not equal
self.number_RW.