Skip to main content
Version: 4.14

Algorithms

Algorithms represent the components of on-board decision making for Guidance, Navigation, and Control. Each Algorithm will only run in certain, user-defined Routines dictated by the active Pointing Mode. Use the Algorithms table to add or edit Algorithms.

Attitude Control

Attitude Control algorithms drive associated Actuators to orient the spacecraft according to the currently active Pointing Mode. Controllers require an attitude estimator to operate. If no estimator is available, the controller will command zero torque on all associated actuators. There are currently two available attitude control Algorithms, each of which relies on Reaction Wheels as the primary actuator with Magnetorquers as an optional secondary for continuous desaturation of the wheels.

Proportional-Integral-Derivative (PID) Control

A basic linear control method, which determines the control u(t)u(t) based on the value (proportional), integral, and derivative of the state (attitude) error e(t)e(t), weighted by the user-defined positive gain values PP, II, and DD, respectively.

u(t)=Pe(t)+I0te(t)dt+Dde(t)dtu(t) = P \,e(t) + I \int_0^t e(t\prime)\, dt\prime + D\, \frac{d e(t)}{dt}

The Sedaro PID controller has an additional gain parameter CC which determines the strength of magnetorquer desaturation. At each timestep the assigned magnetorquers will attempt to reinforce the angular momentum of the wheels J\vec{J}, reducing their angular velocities.

τm(t)CJ(t)\tau_m (t) \leq C \vec{J} (t)

Often the torque will be limited by the rating and orientation of a magnetorquer rather than by CC.

Sliding Mode Control

This is a nonlinear control method, which uses the actuators to force the spacecraft onto a "sliding" manifold in quaternion space. This manifold has the property of the system dynamics are stable around and converge to the commanded attitude. The control law is given below, with the user-defined gains KK, GG, and ϵ\epsilon. [1]

u(t)=ω×Jω(iωi×Jibi)+J(K2sign(δq4)f(q,qd)+Gsat(s,ϵ))\vec{u}(t) = - \vec{\omega} \times \mathbf{J} \vec{\omega} - (\sum_{i} \vec{\omega_i} \times J_i \vec{b}_i) + \mathbf{J} \, (\frac{K}{2} \, \textrm{sign}(\delta q_4) \, \vec{f}(\vec{q}, \vec{q_d}) + G \, \textrm{sat}(\vec{s}, \epsilon))

Where ω\vec{\omega} is the estimated spacecraft angular velocity, J\mathbf{J} the spacecraft inertia, the sum represents the total angular momentum of the reaction wheels, q\vec{q} and qd\vec{q_d} are the measured and commanded quaternions, s\vec{s} is the manifold distance, and sat\textrm{sat} is the saturation function. The value of KK alters the relative weighting between angular rate and angle error, higher values give more weight to angle error. GG scales the overall speed of convergence. Higher values will converge faster but may saturate the actuators. The value of ϵ\epsilon defines a neutral zone for the controller near the desired attitude. Larger values produce more error, but reduce chattering and power use.

Sliding mode control utilizes the same magnetorquer desaturation scheme as in the PID controller, which requires the user defined gain CC.

Attitude Determination

Attitude Determination estimators fuse sensor data into a single estimate of the spacecraft attitude. This estimate can be used for decision-making by other Algorithms. Each estimator type requires one or more associated sensors to operate.

Generic Attitude Determination

A generic attitude determination algorithm that does not have associated sensors but has user-defined error.

Averaging

A simple unweighted averaging algorithm that requires at least one attitude and one angular velocity sensor. This algorithm only considers the current sensor estimates and does not account for satellite dynamics. Let M be a matrix

M=inqiqiT\mathbf{M} = \sum_i^n \vec{q}_i \vec{q}_i^T

where qi\vec{q}_i is the attitude quaternion measured by the ithi^{\textrm{th}} sensor. The average quaternion maximizes qTMq\vec{q}^T \mathbf{M} \vec{q}. [2]

Multiplicative Extended Kalman Filter (MEKF)

A Multiplicative Extended Kalman Filter fuses input from any number of sensors into a single attitude estimate. The filter factors in the expected attitude dynamics of the satellite to predict future states and corrects those predictions based on sensor measurements. This differs from an Additive EKF in that the quaternion components are considered a single state rather than as independent values. At least one attitude sensor is required.

At each timestep, the estimated state is propagated using a simplified attitude dynamics model, which includes control from actuators but excludes environmental perturbations. The estimated covariance matrix PP is updated according to

P˙=FP+PFT+GQGT\dot{\mathbf{P}} = \mathbf{F} \mathbf{P} + \mathbf{P} \mathbf{F}^T + \mathbf{G} \mathbf{Q} \mathbf{G}^T

where F\mathbf{F} and G\mathbf{G} are the Jacobian matrices of the linearized dynamics with respect to the state and noise vectors, respectively. The propagated state x\vec{x} and covariance P\mathbf{P} are combined with new measurements to obtain an updated estimate of each

x~=x+K(yHx)\tilde{x}\prime = \vec{x} + \mathbf{K} (\vec{y} - \mathbf{H} \vec{x}) P~=(IKH)P\tilde{\mathbf{P}}\prime = (\mathbf{I} - \mathbf{K} \mathbf{H}) \mathbf{P}

where y\vec{y} is the measurement from all sensors, H\mathbf{H} is the measurement model and K\mathbf{K} is the optimal gain matrix

K=PHT(HPHT+R)1\mathbf{K} = \mathbf{P} \mathbf{H}^T (\mathbf{H} \mathbf{P} \mathbf{H}^T + \mathbf{R} )^{-1}

where R\mathbf{R} is a diagonal matrix containing the standard deviation for each measurement.

The MEKF has a "fading memory" such that early measurements become less impactful over time as the state measurement converges.[3]

Triaxial Attitude Determination (Triad)

The Triad algorithm produces attitude estimates based on the input from two or more direction sensors. Associated angular rate estimates are derived by averaging measurements from angular rate sensors.

At each timestep, attitude estimation is performed using measurements from two of the associated sensors with available measurement data. The sensors measure two unit vectors b1\vec{b}_1 and b2\vec{b}_2 in the body frame, which are associated to the vectors in the reference frame (r1\vec{r}_1, r2\vec{r}_2) whose values are determined by the satellite's estimated position. The vectors b\vec{b} are related to the reference frame vectors and the attitude matrix A\mathbf{A} by Ari=bi\mathbf{A} \vec{r}_i = \vec{b}_i. Since the two measurements overdetermine the attitude vector, the triad solution satisfies this equation exactly for i=1i = 1 and approximately for i=2i=2.

Let r×=unit(r1×r2)\vec{r}_\times = \textrm{unit}(\vec{r}_1 \times \vec{r}_2) and b×=unit(b1×b2)\vec{b}_\times = \textrm{unit}(\vec{b}_1 \times \vec{b}_2) The estimated attitude matrix is as follows. [3]

Aest=b1r1T+(b1×b×)(r1×r×)T+b×r×T\mathbf{A}_{est} = \vec{b}_1 \vec{r}_1^T + (\vec{b}_1 \times \vec{b}_\times) (\vec{r}_1 \times \vec{r}_\times)^T + \vec{b}_\times \vec{r}_\times^T

The order of the measurements matters, and although many sensors can be selected, only two are used for each estimation. At each timestep, the sensors not producing data are filtered out and the two measurements are chosen from the sensors in increasing order of measurement uncertainty, first from Direction Sensors and then from Vector Sensors.

Orbit Determination

Orbit Determination estimators fuse sensor data into a single estimate of the spacecraft position and velocity. This estimate can be used for decision-making by other Algorithms. Each estimator type requires one or more associated sensors to operate.

Generic Orbit Determination

A generic orbit determination algorithm that does not have associated sensors but has user-defined error

Extended Kalman Filter (EKF)

An Extended Kalman Filter fuses input from any number of sensors into a single position and velocity estimate. The filter factors in the expected orbital dynamics of the satellite to predict future states and corrects those predictions based on sensor measurements. At least one sensor is required.

This algorithm uses the same basis as the MEKF above, operating on state and measurements in linear phase space rather than quaternion space.

GPS Direct

A simple estimation method based on the output of a single GPS unit. Position estimates are derived directly from the sensor and velocity measurements are estimated from two sequential measurements.

Thrust Control

Thrust control algorithms control thrusters so that the spacecraft can perform maneuvers. Static thrust control is currently available, and other algorithms are in development.

Static Thrust Control

The static thrust control algorithm directly assigns thrust values to the associated thrusters as part of the algorithm definition. Assign the thrust values and add this Thrust Control Algorithm to a Pointing Mode to perform the specified burn.

It is recommended to create a pre-maneuver pointing mode to allow the spacecraft attitude to converge to the desired value before entering the pointing mode where the static thrust control algorithm is active.

References

[1] Optimal Variable-Structure Control Tracking of Spacecraft Maneuvers. John L. Crassidis, Srinivas R. Vadali, and F. Landis Markley. Journal of Guidance, Control, and Dynamics 2000 23:3, 564-566. https://doi.org/10.2514/2.4568

[2] Averaging Quaternions. F. Landis Markley, Yang Cheng, John L. Crassidis, and Yaakov Oshman. Journal of Guidance, Control, and Dynamics 2007 30:4, 1193-1197. https://doi.org/10.2514/1.28949

[3] Fundamentals of Spacecraft Attitude Determination and Control. F. Landis Markle, John L. Crassidis. Springer 2014. ISBN : 978-1-4939-0801-1