ADCS.satellite_hardware.satellite.estimated_satellite module¶
- class ADCS.satellite_hardware.satellite.estimated_satellite.EstimatedSatellite(mass=1.0, COM=None, J_0=None, disturbances=[], sensors=[], actuators=[], boresight=None)[source]¶
Bases:
SatelliteSatellite model with estimator-synchronized biases and disturbance parameters.
EstimatedSatelliteextendsSatelliteby tracking additional estimator-driven quantities:actuator bias states (for actuators with
estimate_bias=True),attitude sensor bias states (for sensors with
estimate_bias=True),disturbance parameter states (for disturbances with
estimate_dist=True).
These extra states typically live in an estimator state vector, while the physical simulation maintains internal subsystem objects. This class provides a synchronization bridge between them via
match_estimate().Augmented estimator state layout
The estimator is assumed to output a stacked vector
\[\begin{split}\mathbf{x}_{\mathrm{est}} \;=\; \begin{bmatrix} \mathbf{x} \\ \mathbf{b}_{act} \\ \mathbf{b}_{sens} \\ \boldsymbol{\theta}_{dist} \end{bmatrix},\end{split}\]where
\(\mathbf{x}\in\mathbb{R}^{n_x}\) is the base satellite state used by
Satellite,\(\mathbf{b}_{act}\in\mathbb{R}^{n_{ab}}\) concatenates actuator bias parameters,
\(\mathbf{b}_{sens}\in\mathbb{R}^{n_{sb}}\) concatenates sensor bias parameters,
\(\boldsymbol{\theta}_{dist}\in\mathbb{R}^{n_{dp}}\) concatenates disturbance parameters.
The total expected estimator dimension is:
\[n_{\mathrm{tot}} \;=\; n_x + n_{ab} + n_{sb} + n_{dp}.\]Bias and parameter covariance mapping
The estimator provides a covariance \(\mathbf{P}\) and an integrated covariance \(\int \mathbf{P}\,dt\) (stored as
int_cov).match_estimate()extracts the diagonal blocks corresponding to each bias/parameter group and maps them to per-subsystem standard deviations (square roots of block diagonals).Note
During matching, noise is disabled in actuators/sensors and time variation is disabled in disturbances to ensure deterministic consistency when comparing propagation to estimation.
- Raises:
ValueError – If an estimator state vector with incompatible dimension is provided to
match_estimate().- Parameters:
mass (float)
COM (ndarray)
J_0 (ndarray)
disturbances (List[Disturbance])
sensors (List[Sensor])
actuators (List[Actuator])
boresight (dict[str, ndarray] | ndarray)
- classmethod from_satellite(sat)[source]¶
Create an EstimatedSatellite by cloning a Satellite.
- Parameters:
sat (Satellite)
- Return type:
- control_cov()[source]¶
Block-diagonal covariance of actuator input noise.
For each actuator \(j\), let its input noise covariance be \(\mathbf{R}_{u_j}\) returned by
actuator.noise.cov(). This method constructs:\[\mathbf{R}_u = \mathrm{blkdiag}\left(\mathbf{R}_{u_1}, \mathbf{R}_{u_2}, \dots, \mathbf{R}_{u_{N_u}}\right).\]This covariance is commonly used as the control-noise covariance in stochastic propagation or estimator process-noise modeling.
- Returns:
Block-diagonal actuator noise covariance matrix.
- Return type:
numpy.ndarray
- control_srcov()[source]¶
Block-diagonal square-root covariance of actuator input noise.
For each actuator \(j\), let its square-root covariance be \(\mathbf{S}_{u_j}\) returned by
actuator.noise.srcov()such that:\[\mathbf{R}_{u_j} = \mathbf{S}_{u_j}\mathbf{S}_{u_j}^\top.\]This method constructs:
\[\mathbf{S}_u = \mathrm{blkdiag}\left(\mathbf{S}_{u_1}, \mathbf{S}_{u_2}, \dots, \mathbf{S}_{u_{N_u}}\right).\]- Returns:
Block-diagonal actuator noise square-root covariance matrix.
- Return type:
numpy.ndarray
- dist_torque_hess(x, vecs)[source]¶
Hessians of total disturbance torque w.r.t. state and disturbance parameters.
This overrides
dist_torque_hess()by populating parameter–parameter and quaternion–parameter second derivatives for disturbances with estimated parameters.Let \(\boldsymbol{\tau}_d(\mathbf{x},\boldsymbol{\theta}_d)\) be the total disturbance torque. This method returns:
\[\mathbf{H}_{xx} = \frac{\partial^2 \boldsymbol{\tau}_d}{\partial \mathbf{x}^2}, \qquad \mathbf{H}_{x\theta} = \frac{\partial^2 \boldsymbol{\tau}_d}{\partial \mathbf{x}\,\partial \boldsymbol{\theta}_d}, \qquad \mathbf{H}_{\theta\theta} = \frac{\partial^2 \boldsymbol{\tau}_d}{\partial \boldsymbol{\theta}_d^2}.\]State Hessian sparsity
As in the base class, only quaternion components contribute to state second derivatives:
\[\mathbf{H}_{xx}[3:7,3:7,:] = \sum_i \frac{\partial^2 \boldsymbol{\tau}_{d,i}}{\partial \mathbf{q}^2}.\]Parameter blocks
For each estimated disturbance \(i\) with parameter vector size \(\ell_i\), the method places:
\[\mathbf{H}_{\theta\theta}[k:k+\ell_i,\,k:k+\ell_i,:] = \frac{\partial^2 \boldsymbol{\tau}_{d,i}}{\partial \boldsymbol{\theta}_{d,i}^2},\]and
\[\mathbf{H}_{x\theta}[3:7,\,k:k+\ell_i,:] = \frac{\partial^2 \boldsymbol{\tau}_{d,i}}{\partial \mathbf{q}\,\partial \boldsymbol{\theta}_{d,i}}.\]Each estimated disturbance is expected to implement:
torque_qqhess(self, vecs)→ \(\partial^2 \boldsymbol{\tau}/\partial\mathbf{q}^2\),torque_qvalhess(self, vecs)→ \(\partial^2 \boldsymbol{\tau}/\partial\mathbf{q}\partial\boldsymbol{\theta}\),torque_valvalhess(self, vecs)→ \(\partial^2 \boldsymbol{\tau}/\partial\boldsymbol{\theta}^2\).
- Parameters:
x (numpy.ndarray) – Current base spacecraft state vector, shape
(state_len,).vecs (dict[str, numpy.ndarray]) – Dictionary containing body-frame environment vectors and their derivatives.
- Returns:
Tuple
(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_jacobian(x, vecs)[source]¶
Jacobians of total disturbance torque w.r.t. state and disturbance parameters.
This overrides
dist_torques_jacobian()by additionally returning the derivative of the total disturbance torque w.r.t. estimated disturbance parameters.Let the total disturbance torque be
\[\boldsymbol{\tau}_d(\mathbf{x},\boldsymbol{\theta}_d) = \sum_{i=1}^{N_d}\boldsymbol{\tau}_{d,i}(\mathbf{x},\boldsymbol{\theta}_{d,i}).\]The method returns:
\[\mathbf{J}_x = \frac{\partial \boldsymbol{\tau}_d}{\partial \mathbf{x}}, \qquad \mathbf{J}_{\theta} = \frac{\partial \boldsymbol{\tau}_d}{\partial \boldsymbol{\theta}_d}.\]State Jacobian structure
Only attitude (quaternion) affects rotated environment vectors and thus torque for the provided disturbance interface; therefore:
\[\mathbf{J}_x[3:7,:] = \sum_i \frac{\partial \boldsymbol{\tau}_{d,i}}{\partial \mathbf{q}},\qquad \mathbf{J}_x[k,:]=0\;\text{for}\;k\notin\{3,4,5,6\}.\]Parameter Jacobian assembly
If
self.dist_param_len > 0, the parameter Jacobian is formed by vertically stacking each estimated disturbance’s parameter Jacobian:\[\begin{split}\mathbf{J}_{\theta} = \begin{bmatrix} \frac{\partial \boldsymbol{\tau}_{d,i_1}}{\partial \boldsymbol{\theta}_{d,i_1}} \\ \vdots \\ \frac{\partial \boldsymbol{\tau}_{d,i_m}}{\partial \boldsymbol{\theta}_{d,i_m}} \end{bmatrix}.\end{split}\]Each estimated disturbance is expected to implement:
torque_qjac(self, vecs)→ \(\partial \boldsymbol{\tau}/\partial\mathbf{q}\),torque_valjac(self, vecs)→ \(\partial \boldsymbol{\tau}/\partial\boldsymbol{\theta}\).
- Parameters:
x (numpy.ndarray) – Current base spacecraft state vector, shape
(state_len,).vecs (dict[str, numpy.ndarray]) – Dictionary containing body-frame environment vectors and their quaternion derivatives, typically including keys like
"b","r","s","v","rho", and derivative keys like"db","dr","ds","dv".
- Returns:
Tuple
(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]¶
Jacobians of augmented dynamics w.r.t. state, inputs, and estimated parameters.
This method extends the base linearization from
dynJacCore()by additionally returning Jacobians of \(\dot{\mathbf{x}}\) w.r.t.:actuator bias vector \(\mathbf{b}_{act}\),
sensor bias vector \(\mathbf{b}_{sens}\) (typically zeros for the process model),
disturbance parameter vector \(\boldsymbol{\theta}_{dist}\).
The local first-order model is:
\[\delta\dot{\mathbf{x}} \approx \mathbf{A}\,\delta\mathbf{x} + \mathbf{B}\,\delta\mathbf{u} + \mathbf{G}_{ab}\,\delta\mathbf{b}_{act} + \mathbf{G}_{sb}\,\delta\mathbf{b}_{sens} + \mathbf{G}_{dp}\,\delta\boldsymbol{\theta}_{dist}.\]Returned blocks
The method returns a list:
\[\left[ \frac{\partial \dot{\mathbf{x}}}{\partial \mathbf{x}}, \frac{\partial \dot{\mathbf{x}}}{\partial \mathbf{u}}, \frac{\partial \dot{\mathbf{x}}}{\partial \mathbf{b}_{act}}, \frac{\partial \dot{\mathbf{x}}}{\partial \mathbf{b}_{sens}}, \frac{\partial \dot{\mathbf{x}}}{\partial \boldsymbol{\theta}_{dist}} \right].\]Where the last three blocks are assembled via actuator- and disturbance-provided derivatives:
actuators implement
dtorq__dbiasand (if wheels) storage-torque bias derivatives,disturbances provide parameter Jacobians via
dist_torques_jacobian().
Note
Sensor bias Jacobians are typically zero in the process model because sensor biases affect measurements, not rotational dynamics; therefore
dxdot__dsbis returned as zeros.- Parameters:
x (numpy.ndarray) – Current base state vector, shape
(state_len,).u (numpy.ndarray) – Current control vector, shape
(control_len,).orbital_state (
Orbital_State) – Orbital/environmental state supplying ECI vectors and scalars used by torque models.
- Returns:
List
[dxdot__dx, dxdot__du, dxdot__dab, dxdot__dsb, dxdot__ddmp].- Return type:
list[numpy.ndarray]
Return shapes
Name
Shape
dxdot__dx(state_len, state_len)dxdot__du(control_len, state_len)dxdot__dab(act_bias_len, state_len)dxdot__dsb(att_sens_bias_len, state_len)dxdot__ddmp(dist_param_len, state_len)
- dynamics_Hessians(x, u, orbital_state)[source]¶
Second-order derivatives (Hessians) of augmented dynamics.
This method computes second derivatives of the base rotational dynamics and extends them to include curvature terms w.r.t. actuator biases and disturbance parameters. The Hessians are organized as a block matrix over the stacked variable vector
\[\begin{split}\mathbf{z} = \begin{bmatrix} \mathbf{x} \\ \mathbf{u} \\ \mathbf{b}_{act} \\ \mathbf{b}_{sens} \\ \boldsymbol{\theta}_{dist} \end{bmatrix}.\end{split}\]For each state-derivative component \(\dot{x}_k\), the Hessian stores
\[\frac{\partial^2 \dot{x}_k}{\partial z_i\,\partial z_j}.\]Returned structure
If reaction wheels are present (and extended estimation terms are active), the method returns:
[ [ddxdot__dxdx, ddxdot__dxdu, ddxdot__dxdab, ddxdot__dxdsb, ddxdot__dxddmp], [ddxdot__dxdu.T, ddxdot__dudu, ddxdot__dudab, ddxdot__dudsb, ddxdot__duddmp], [0, 0, ddxdot__dabdab, ddxdot__dabdsb, ddxdot__dabddmp], [0, 0, 0, ddxdot__dsbdsb, ddxdot__dsbddmp], [0, 0, 0, 0, ddxdot__ddmpddmp] ]
If extended estimation terms are not used, it falls back to the base 2×2 structure:
[ [ddxdot__dxdx, ddxdot__dxdu], [ddxdot__dxdu.T, ddxdot__dudu] ]
Key analytic contributions
Quaternion kinematics curvature terms from \(\dot{\mathbf{q}} = \tfrac12 W(\mathbf{q})^\top\boldsymbol{\omega}\).
Rigid-body dynamics curvature from the gyroscopic term \(-\boldsymbol{\omega}\times(\mathbf{J}\boldsymbol{\omega} + \mathbf{H}_{RW})\).
Disturbance torque curvature terms from
dist_torque_hess().Actuator torque curvature terms from actuator-provided second derivatives, including bias couplings.
- Parameters:
x (numpy.ndarray) – Current base state vector, shape
(state_len,).u (numpy.ndarray) – Current control vector, shape
(control_len,).orbital_state (
Orbital_State) – Orbital/environmental state providing ECI vectors and scalars for torque models.
- Returns:
Nested list of Hessian tensors (see structure above).
- Return type:
list[list[numpy.ndarray]]
Common tensor shapes (extended case)
Tensor
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)ddxdot__dxdab(state_len, act_bias_len, state_len)ddxdot__dxdsb(state_len, att_sens_bias_len, state_len)ddxdot__dxddmp(state_len, dist_param_len, state_len)ddxdot__dabdab(act_bias_len, act_bias_len, state_len)ddxdot__dsbdsb(att_sens_bias_len, att_sens_bias_len, state_len)ddxdot__ddmpddmp(dist_param_len, dist_param_len, state_len)
- match_estimate(est_state, dt)[source]¶
Synchronize the satellite instance with the estimator output.
This method maps the estimator output into the simulation model by:
Extracting wheel momenta from the base state portion and updating wheel objects via
update_RWhs().Writing actuator biases into each actuator’s bias object and setting per-bias standard deviations from the corresponding covariance block.
Writing sensor biases into each attitude sensor’s bias object and setting per-bias standard deviations from the corresponding covariance block.
Writing disturbance parameters into each disturbance model (for active disturbances) and setting their parameter standard deviations from covariance blocks.
For deterministic matching, disabling: *
actuator.use_noise = Falsefor all actuators, *sensor.use_noise = Falsefor all sensors, *disturbance.time_varying = Falsefor all disturbances.
Estimator vector partition
With
\[\begin{split}\mathbf{x}_{\mathrm{est}} = \begin{bmatrix} \mathbf{x} \\ \mathbf{b}_{act} \\ \mathbf{b}_{sens} \\ \boldsymbol{\theta}_{dist} \end{bmatrix},\end{split}\]indices are:
\[\begin{split}\begin{aligned} \mathbf{x} &\in \mathbb{R}^{n_x},\\ \mathbf{b}_{act} &\in \mathbb{R}^{n_{ab}},\\ \mathbf{b}_{sens} &\in \mathbb{R}^{n_{sb}},\\ \boldsymbol{\theta}_{dist} &\in \mathbb{R}^{n_{dp}}, \end{aligned}\end{split}\]where
\[n_x=\texttt{self.state\_len},\; n_{ab}=\texttt{self.act\_bias\_len},\; n_{sb}=\texttt{self.att\_sens\_bias\_len},\; n_{dp}=\texttt{self.dist\_param\_len}.\]Covariance-to-standard-deviation mapping
For each extracted block covariance \(\mathbf{P}_{block}\), per-element standard deviations are assigned as:
\[\boldsymbol{\sigma} = \sqrt{\operatorname{diag}(\mathbf{P}_{block})}.\]In the implementation, the estimator provides an integrated covariance block (
int_cov) that may be dimension-shifted by one element in some configurations (e.g., quaternion handling). The method applies an index adjustmentadjwhenint_covis off-by-one.- Parameters:
est_state (
EstimatedArray) – Estimator output container providingval(state vector),cov(covariance), andint_cov(integrated covariance).dt (float) – Estimator propagation step (s). Used by some pipelines to normalize integrated covariance. (The current implementation partitions
int_covdirectly.)
- Returns:
None.- Return type:
None
- Raises:
ValueError – If
est_state.valdoes not have lengthself.state_len + self.act_bias_len + self.att_sens_bias_len + self.dist_param_len.
- sensor_bias_slice(att_sensor_index)[source]¶
Slice for an attitude sensor’s bias block in the full estimator state vector.
The full estimator state is assumed to be ordered as:
\[\begin{split}\mathbf{x}_{\mathrm{est}} = \begin{bmatrix} \mathbf{x} \\ \mathbf{b}_{act} \\ \mathbf{b}_{sens} \\ \boldsymbol{\theta}_{dist} \end{bmatrix},\end{split}\]where the sensor-bias block starts at offset:
\[k_0 = n_x + n_{ab} \;=\; \texttt{self.state\_len} + \texttt{self.act\_bias\_len}.\]This method returns the Python
slice(start, stop)selecting the bias elements forself.attitude_sensors[att_sensor_index]within \(\mathbf{x}_{\mathrm{est}}\). If the specified sensor does not have an estimated bias (i.e., not inatt_sens_bias_inds), the method returnsNone.- Parameters:
att_sensor_index (int) – Index into
self.attitude_sensors.- Returns:
Slice selecting the sensor’s bias portion in the estimator vector, or
None.- Return type:
slice | None
- Raises:
RuntimeError – If the sensor index is listed as bias-estimated but the slice cannot be constructed.
- sensor_cov(which_sensors)[source]¶
Block-diagonal covariance of attitude sensor noise (and wheel momentum measurement noise).
For each attitude sensor \(i\) with covariance \(\mathbf{R}_{y_i}\) (from
sensor.noise.cov()), the attitude-sensor covariance is:\[\mathbf{R}_y = \mathrm{blkdiag}\left(\mathbf{R}_{y_{i_1}}, \dots, \mathbf{R}_{y_{i_m}}\right),\]where the set \(\{i_1,\dots,i_m\}\) is selected by
which_sensors.If reaction wheels are present, each wheel contributes an additional measurement covariance for its momentum measurement model (e.g.,
rw.h_meas_noise.cov()), appended to the block diagonal.- Parameters:
which_sensors (list[bool]) – Boolean selector list of length
len(self.attitude_sensors)indicating which attitude sensors to include. IfNoneis passed in the implementation, all are included.- Returns:
Block-diagonal measurement covariance matrix. If no sensors are selected, returns a
(0,0)array.- Return type:
numpy.ndarray
- sensor_srcov(which_sensors)[source]¶
Block-diagonal square-root covariance of attitude sensor noise (and wheel momentum measurement noise).
For each attitude sensor \(i\) with square-root covariance \(\mathbf{S}_{y_i}\) (from
sensor.noise.srcov()) such that \(\mathbf{R}_{y_i}=\mathbf{S}_{y_i}\mathbf{S}_{y_i}^\top\), this method constructs\[\mathbf{S}_y = \mathrm{blkdiag}\left(\mathbf{S}_{y_{i_1}}, \dots, \mathbf{S}_{y_{i_m}}\right),\]with selection controlled by
which_sensors.If reaction wheels are present, each wheel contributes an additional square-root covariance block for its momentum measurement model (e.g.,
rw.h_meas_noise.srcov()).- Parameters:
which_sensors (list[bool]) – Boolean selector list of length
len(self.attitude_sensors)indicating which attitude sensors to include. IfNoneis passed in the implementation, all are included.- Returns:
Block-diagonal measurement square-root covariance matrix. If no sensors are selected, returns a
(0,0)array.- Return type:
numpy.ndarray