Open access peer-reviewed chapter

Modern Control System Learning

Written By

Brendon Smeresky and Alex Rizzo

Submitted: 18 May 2019 Reviewed: 17 October 2019 Published: 27 May 2020

DOI: 10.5772/intechopen.90198

From the Edited Volume

Deterministic Artificial Intelligence

Edited by Timothy Sands

Chapter metrics overview

731 Chapter Downloads

View Full Metrics

Abstract

This manuscript will explore and analyze the effects of different controllers in an overall spacecraft’s attitude determination and control system (ADCS). The experimental setup will include comparing an ideal nonlinear feedforward controller, a feedback controller, and a combined ideal nonlinear feedforward + feedback controller within a Simulink simulation. A custom proportional, derivative, integral controller was implemented in the feedback control, adding an additional term to account for the nonlinear coupled motion. Consistent proportional, derivative, and integral gains were used throughout the duration of the experiment. The simulated results will show that the ideal nonlinear feedforward controller lacked an error correction mechanism and took extra time to execute, the feedback controller faired only slightly better, but the combined ideal nonlinear feedforward controller with feedback correction yielded the highest accuracy with the lowest execution time. This highlights the potential effectiveness for a learning control system.

Keywords

  • control systems
  • feedforward
  • feedback
  • learning systems

1. Introduction

The goal of a spacecraft’s attitude determination and control system (ADCS) is to have a system that can move to and hold a specific orientation in three-dimensional space, relative to an inertial frame. This project can be viewed through three different lenses: classical control, modern control, and/or machine learning. These lenses explain the same control theory in three different contexts. For all the control theories, the ADCS considers the kinetics, kinematics, disturbances, controls, and actuators that dictate the system’s motion [1]. Specifically, with regard to classical control, both feedforward and feedback controller are implemented in order to eliminate the error between a desired and commanded signal [1]. With regard to modern control, a similar estimation and correction method is implemented using either an extended Kalman controller, which relies upon on a nonlinear control estimator coupled with a linear control corrector, or an unscented Kalman controller, which uses both a nonlinear control estimator and nonlinear control corrector, in order to reduce error [2, 3, 4, 5, 6]. The third context relates control systems to deterministic artificial intelligence and machine learning. The control estimate derives from self-awareness of its own attributes that update every time-step with new information. This self-updating learning mechanism can be viewed akin to the update cycle used by supervised learning algorithms to model a system’s performance. As an example, the updating mechanism is either a linear or nonlinear method to update an unknown inertia matrix for a spacecraft [7, 8, 9, 10, 11, 12, 13].

Figure 1 depicts the topology of the computational steps that take desired angle inputs and calculates Euler angle outputs: φ, θ, and ψ. The desired angle inputs are processed through the trajectory, controls, actuators, dynamics, and disturbances blocks. Section II will explain the theory behind the overall control system, Section III will detail the experimental setup, Section IV will show the results, and Section V will conclude this paper.

Figure 1.

The overview of the control system from the desired φ, θ, and ψ inputs (white box), through calculations steps (light gray boxes) to φ, θ, and ψ Euler angle outputs (dark gray box).

Advertisement

2. Background and theory

The rotation maneuver from one position to another is measured from the inertial reference frame or [XI, YI, ZI] to the final position, the body reference frame or [XB, YB, ZB], as depicted in Figure 2. For this simulation, a model was created to rotate from orientation A, [XA, YA, ZA], to orientation B, [XB, YB, ZB]. The kinetics, kinematics, orbital frame, and disturbance calculations are explained in Ref. [1]. This paper focuses on a combined feedforward plus feedback controller as an error estimation and correction mechanism. This simulation utilizes three control moment gyroscopes (CMG) that are responsible for physically moving the system according to the inputted control signal. Additionally, this paper will focus on how the control system implementation affects the rotational maneuver and final orientation of a spacecraft.

Figure 2.

Execution of a rotation from XI to XB; blue arrows denote angle rotations which can be seen to rotate around the quaternion axis, q4 in red.

2.1 Control moment gyroscopes

A CMG acts like a large reaction wheel spinning at a constant speed that transfers energy by changing its orientation. It successfully induces motion by following the governing equations of rotational mechanics, detailed in Eqs. (1) and (2):

T=Ḣs+ω×Hs=u=ḢE1
Hs=+hE2

These governing equations apply to any rotating, rigid body of mass. T represents the torque which is equal to the optimal control, u; Hs represents the total system’s angular momentum; ω represents the angular velocity of the body; J is the inertia matrix for the entire body, including the CMGs; and h is the momentum produced by the CMGs. All these variables are expressed in the body frame of the spacecraft.

Physically on a spacecraft, the CMGs are typically one of several cylinders located at different orientations within the spacecraft’s bus, used to perform reorientation maneuvers. In Figure 1, the CMGs are represented within the actuators block, which is directly before the dynamics block. The actuator input is a commanded torque u=Ḣ, and the output is an actual torque that is fed to the system using a sinusoidal trajectory described in [14].

The method of transforming a commanded torque, T, into an actual torque using the CMGs is described in Eqs. (3), (4), and (5). In these equations, the variable θi is the rotation about the gimbal axis, and β is the skew angle orientation of the respective CMG. The notations have also been shortened so that sine and cosine trig functions are “s” and “c,” respectively:

A=δHδθ=sinθ1cosβ2cosθ2sinθ3cosβ1cosθ1sinθ2cosβ3cosθ3sinβ1cosθ1sinβ2cosθ2sinβ3cosθ3E3
A1Ḣ=A1Aθ̇=θ̇E4
A1=cθ3cθ1sθ3+sθ1θ3sθ3cθ1sθ3+sθ1θ3tθ2sθ3cθ1sθ3+sθ1θ301sθ20cθ1cθ1sθ3+sθ1θ3sθ1cθ1sθ3+sθ1θ3tθ2sθ1cθ1sθ3+sθ1θ3E5

The first step is to build [A], commonly referred to as the Jacobian matrix or the spatial matrix. This matrix takes the angular changes in H and compares them to the changes in θi. This concept is visually represented in Figure 3, given a fixed β and fixed θi from (3).

Figure 3.

CMG diagram with blue for axes and β angles, red for angular momentum vectors, green for θ rotation axes, and purple for the direction of θ rotation.

The second step is based on the “so-called” inverse steering law, which is represented in (4). This equation relates the commanded torque to the gimbal rate, where the commanded torque is also known as the rate of change of the angular momentum. This calculation can be done with a variety of methods. A few potential methods for inversion include singular value decomposition, matrix inversion for square matrices, matrix pseudo-inversion for non-square matrices, or element by element in [A]−1 as defined in (5). Each of these methods yields a commanded gimbal rate, θ̇. For simplification, the actuator is assumed to be perfect and produces the actual gimbal rate commanded without error or loss.

The last step is to invoke the inverse steering law in (6) to relate the Jacobian matrix to the actual gimbal rate and determine the actual torque produced. This can be completed using decoupled equations, as shown in [15]:

T=Aθ̇=ḢE6

Alternatively, Eqs. (4), (5), and (6) can be combined algorithmically and solved for using Eq. (7):

detA=sθ1sθ2sβcθ3cβcθ3sβcθ2+cβcθ2cβcθ1sβcθ3+cβcθ3sβcθ1+sθ3cβcθ1sβcθ2+sθ2sβcθ1whereβ1β2β3E7

In one calculated step, an output torque is yielded. This torque will feed into the dynamics as described in (1), using the process detailed above and in [1].

2.2 Singularities

A singularity occurs when an element in the Jacobian matrix, from (3), is resolved to an undefined value. This is caused by a zero existing within the denominator of (5), which complicates the calculation when solving for the determinant of [A]. Eq. (7) shows that singularities depend upon θ1, θ2, θ3, β1, β2, and β3 values. Conceptually, this occurs at certain θ and β combinations because infinite torque is required to move the CMG when the torque vector is orthogonal to the gimbal axis. Trying to do so is impossible and yields unstable behavior as the CMG acts erroneously and tries to resolve a 1/0 calculation and command an undefined torque. Furthermore, when all the β angles are equal, β1 = β2 = β3, (7) simplifies further but is depicted as is for thoroughness.

This analysis is completed by taking (7) and stepping through θ and β combinations to verify which yield a zero determinant. For example, with sin θ1, cos β2, cos θ2, and sin θ3 all equal 0, the determinant of [A] is zero, yielding a possible solution of θ1 = θ2 = θ3 = 0°. However, this is a long process with the many permutations of solutions, which are omitted in this manuscript [15].

2.3 Controllers and observers

The input to a CMG is a torque vector, [Tx, Ty, Tz], which is a signal generated by the trajectory block in Figure 1. However, this signal is not tuned to adjust to real world influences, where mechanical hardware can introduce errors due to incorrectly or un-modeled attributes, noise, etc. In order to overcome these losses, either a feedforward controller, a feedback controller, or a combination of both controllers can be used to counter introduce errors. More specifically, proportional, integral, and derivative (PID) gains are correlated to the position error generated when moving from one position to another position to correct the errors. However, using only the position error eθ, its integral eθdt and its derivative ddteθ result in inaccuracies. This is due to the derivative calculation, which is both inefficient and inaccurate as a result of the virtual-zero reference created in the cascaded topology of a PID controller when the computation is initialized [16, 17, 18, 19]. This inaccuracy can be prevented by sending in both the position error and the velocity error, which has been done in this experiment via an enhanced Luenberger proportional, derivative, integral (PDI) controller [16, 17, 18, 19]. Additionally, the enhanced Luenberger controller differs from the conventional PID controller which only receives a position error. The result is a controller that outputs a commanded torque to the actuator block in Figure 1. Topologies are shown of the overall feedback controller in Figure 4, and the enhanced Luenberger PDI controller in Figure 5.

Figure 4.

Topology of a feedback controller with two methods of control: A classic PID controller or an enhanced Luenberger PDI controller.

Figure 5.

PDI controller with ω input to remove virtual-zero reference with Kp, Kd, and Ki gains.

The simulation in this experiment utilized an observer to eliminate the virtual-zero reference described above. An observer is comparable to a controller as they both take in a position via system sensors and output a twice differentiated term to produce full-state feedback knowledge. However, it provides an advantage: because it is not implemented on a specific piece of hardware, much higher gains can be utilized than can be used otherwise. A topology of the observer is shown in Figure 6 in the controller/observer block.

Figure 6.

Topology of an observer based upon a PID controller and two sets of differentiation to yield full-state knowledge.

2.4 Control system learning

A control system is capable of learning by estimating its desired position and then updating the control to correct for errors. In a learning control system, the control estimator is the feedforward controller defined by (8), and the corrector or learning mechanism is the feedback controller defined by (9), where Φ and Θ are defined by (10) and (11), respectively. The feedback controller can also be written in terms of the gains and the position error, eθ, as shown in (12). Combining (8) and (9) yields a learning system that develops a more accurate control over time through (13):

uff=T=Jωḋ+ωd×Jωd=ΦΘE8
ufb=ΦΘ̂=ΦΦTΦ1ΦTδuE9
Φ=ω̇xω̇yω̇zωxωzω̇x0ωxωy0ω̇xωyωz0ωzωyω̇yω̇zωzωxωyωxω̇yω̇zE10
Θ=JxxJxyJxzJyyJyzJzzTE11
ufb=kpeθ+kdeθ̇+kieθE12
utot=uff+ufb=Jωḋ+ωd×Jωd+ΦΦTΦ1ΦTδu=ΦΘ+ΦΦTΦ1ΦTdu=ΦΘ+ΦTΦ1ΦTδuE13

Overall, the term “ΦΘ̂” in (9) represents the self-awareness statement. The nonlinear state transition matrix, Φ, was built by knowing the dynamics of the system, and Θ̂ is the vector of unknown variables. Another application includes analyzing a changing inertia matrix, where it is assumed that the mass of the system is varying. The vector of unknowns, Θ̂, is the learned moment of inertia that is recalculated at every iteration of the model and determining its new mass [9].

Advertisement

3. Experimental setup

This manuscript documents the implementation of three different control algorithm combinations to induce a yawing motion on a spacecraft by generating the commanded torque to a three-gimballed spacecraft ACS. The three cases are a nonlinear feedforward control (case 1), a linear feedback control (case 2), and a combination of both nonlinear feedforward + linear feedback (case 3). The gains for these controllers are found in Table 1.

Kp gainKd gainKi gain
PDI controller1000100.1
Observer100,0005000.1

Table 1.

Tuned gain values for the PDI controller and observer.

The model in this manuscript was built in MATLAB and Simulink, where integrations were calculated using the ode45 with the Runge–Kutta solver and a fixed time-step. Euler angles were resolved using a 3-2-1 rotation sequence with the atan2 trigonometry function.

As per [1], initialized values include torque = [0,0,0] and quaternion = [0,0,0,1]. The spacecraft’s inertia matrix is J = [10,0.1,0.1; 0.1,10,0.1; 0.1,0.1,10]. The disturbances are defined in [1]. The orbital altitude was set at 150 km with a drag coefficient of 2.5 and orbital motion off. Each simulation executed over a five-second quiescent period, five-second maneuver time, and five-second post-maneuver observation period, totaling 60 seconds and yielding a ωf=π/2 and φ=π/2 for the sinusoidal trajectory of the controller.

Advertisement

4. Experimental results and analysis

4.1 Time-step analysis

Time-step analysis was completed to determine whether reducing the time-step would help minimize the body frame to the inertial frame error deviations. The results of executing a maneuver with a feedforward + feedback controller utilizing two different time-steps are depicted in Figure 7. Expectations were that a smaller time-step would result in more precise results, meaning a smaller deviation between the commanded and executed Euler angles. However, comparing the red and blue trajectories within each of the three plots in Figure 7 shows that although some refinement is gained by decreasing the time-step, the gain is minimal. Therefore, a larger time-step can be used without losing much accuracy.

Figure 7.

Time-step analysis for the ϕ, θ, and ψ Euler angles for two time-steps.

Comparing the θactual − θdesired and ωactual − ωdesired errors for time-steps of 0.01 and 0.001 in Figure 8 yielded a similar result. The θz channel did receive the greatest amount of refinement with a smaller time-step, but no order of magnitude increase resulted. Therefore, these results confirm that varying the time-step has limited impact on the trajectories. Therefore, for the gains in Table 1, a minimum time-step of 0.01 is recommended, and decreasing it provides no additional benefit.

Figure 8.

Time-step analysis comparing θactual−θdesired and ωactual−ωdesired errors.

4.2 Control implementation

The performance of the three control system implementations is depicted in Figure 9. Comparing the three cases allowed further analysis on the differences between feedforward, feedback, and the combined feedforward + feedback control system. The feedforward and feedforward + feedback controllers are more precise than the feedback method. This is because it is based off an exact control equation, Eq. (8). Conversely, the feedback controller is based off a PDI controller that has one time-step of induced lag and is therefore less precise. Additionally, the gains in a PDI or PID controller must be finely tuned with predetermined gain values, which can be an iterative and time-consuming task because controller performance varies greatly depending on the values. Lastly, the combined controller configuration represents an error combination of both the feedforward and feedback plots. It allows the analytical accuracy of the feedforward equation to be updated with the responsiveness of the feedback correction, but too little error exists in this case for the results to be visible.

Figure 9.

Controller error over time for the three configurations.

Figure 10 shows the error of the commanded Euler angle over time. The two left-most plots in Figure 10 show that the error is different for each controller. The feedback controller fluctuates initially as it corrects to minimize error over time. The feedforward controller is excellent initially but slowly deviates as error accrues without correction. Lastly, the combined controller is the best of both and starts with minimal error but then corrects that error over time. However, note that the error is minimal because no movement was commanded in either the φ or θ channels; the residual error exists because of cross-chatter between channels resultant from Eqs. (3) and (5).

Figure 10.

Euler angle error for the three controller configurations.

The third plot from the left shows the position error in the ψ channel, which is the channel in which a 30-degree maneuver was commanded. Before the maneuver was started, the desired versus commanded error starts at 30°. At each time-step, the position is updated and the error decreases. Due to the scale of the maneuver, all three controllers appear to do well during the maneuver. To better understand the performance, the fourth and right-most plot is a zoom-in of the third plot, illustrating the accuracies of the feedforward controller due to the forward propagation accuracy of (8), the lag induced error and imperfect gain tuning of the feedback controller, and the results of the combined feedforward + feedback controllers. It is a better example of how each controller operates: the feedforward controller again starts off with minimal error before deviating over time, the feedback controller starts with the greatest amount of error that is overshot and damped, and the combined controller, which is the best of both the minimal starting error and correction capability of the other controllers.

Lastly, Table 2 compares the boundary condition satisfaction at the final time of the maneuver. The results show that the feedforward + feedback controller has both the least amount of error and the shortest runtime. Conversely, the feedforward controller is the worst in both accuracy and runtime but only by a small margin compared to the feedback controller. The feedforward controller is hypothesized to perform worse because (12) tries to model (1) but can only poorly approximate it, yielding inaccuracies, which accrue over time.

φactual − φdesiredθactual − θdesiredψactual − ψdesiredRun time (seconds)
uff−3.93e-04°4.18e-04°−1.48e-02°20.7
ufb6.03e-09°−9.01e-08°4.66e-08°20.5
uff+fb1.06e–08°−7.94e-09°4.38e-09°20.3

Table 2.

The actual-desired Euler angle errors for the three cases using a 0.001 time-step and their associated run times.

Figure 11 is a revisualization of the data in Figure 10. This depiction is more intuitive and breaks down the change in angular position over time for each controller, as well as magnifying the post-maneuver oscillations and damping. Commanding [0;0;30], we see that all controller configurations are responsive to this input, with the expected differences. The accuracy of the feedforward control in the left-most plots, combined with the undamped response of feedback control of the middle plots, gives dampened response of the combined controller in the right-most plots.

Figure 11.

Change in angular position for all three controller configurations.

Advertisement

5. Conclusion

This experiment implemented and compared the effects of a feedforward, feedback, and a combined forward + feedback control system. A yaw maneuver was commanded, and the response was measured to show that an ADCS can estimate and then update its control over time, similar to a feedforward and feedback learning mechanism. The results showed that the feedforward controller lacks a correction mechanism that accrues error and takes time; the feedback system is slightly better in both metrics, but the combined feedforward + feedback system combines the best of both systems for superior accuracy in the shortest time. Therefore, the combined system is the best choice for its accuracy and adaptability. However, this combined system needs to be further researched by subjecting the system to noise and induced disturbances to validate the combined system’s responsiveness.

Advertisement

Acknowledgments

We would like to thank our teacher, Dr. Timothy Sands, for his guidance in developing this work, as well as our families for their support while we spent our time away from them developing this research, so thank you.

Advertisement

Conflict of interest

The authors declare no conflict of interest.

References

  1. 1. Smeresky B, Rizzo A, Sands T. Kinematics in the information age. Mathematics. 2018;6(9):148
  2. 2. Kalman RE. A new approach to linear filtering and prediction problems. Journal of Basic Engineering. 1960;82:35-45
  3. 3. McElhoe BA. An assessment of the navigation and course corrections for a manned flyby of Mars or Venus. IEEE Transactions on Aerospace and Electronic Systems. 1966;2(4):613-623
  4. 4. Julier SJ, Uhlmann JK, UKF. New extension of the Kalman filter to nonlinear systems. In: Signal Processing, Sensor Fusion, and Target Recognition VI. Proceedings of SPIE. 3. pp. 182-193
  5. 5. Sands T. Nonlinear-adaptive mathematical system identification. Computation. 2017;5:47
  6. 6. Kalman RE. Contributions to the theory of optimal control. In: Boletín de la Sociedad Matemática Mexicana. 1960;5(2). pp. 102-119
  7. 7. Nakatani S, Sands T. Battle-damage tolerant automatic controls. Electrical and Electronic Engineering. 2018;8(1):23
  8. 8. Nakatani S, Sands T. Simulation of spacecraft damage tolerance and adaptive controls. IEEE Aerospace. 2014;1-16:2014
  9. 9. S Nakatani T. Sands, nonlinear adaptive control: Autonomous damage recovery in space. International Journal of Control, Automation and Systems. 2016;2:23-36
  10. 10. Sands T, Kim JJ, Agrawal BN. Spacecraft fine tracking pointing using adaptive control. In: Proceedings of 52th International Astronautical Congress; 2007
  11. 11. Sands T, Kim JJ, Agrawal B. Spacecraft Adaptive Control Evaluation. Infotech@ Aerospace 2012, 2476
  12. 12. Sands T, Kim JJ, Agrawal BN. Improved Hamiltonian adaptive control of spacecraft. In: 2009 IEEE Aerospace Conference. 1-10; 2009
  13. 13. Cooper M, Heidlauf P, Sands T. Controlling chaos – Forced van der pol equation. Mathematics. 2017;5(4):70
  14. 14. Baker K, Cooper M, Heidlauf P, Sands T. Autonomous trajectory generation for deterministic artificial intelligence. Electrical and Electronic Engineering. 2018;8:59-68. DOI: 10.5923/j.eee.20180803.01
  15. 15. Sands TA, Kim JJ, Agrawal B. Control moment gyroscope singularity reduction via decoupled control. In: IEEE SEC 2009, 388-391; 2009
  16. 16. Sands T., Lorenz R. Physics-based automated control of spacecraft. In: Proceedings of the AIAA Space Conference & Exposition; Pasadena, CA, USA; 14–17 September 2009
  17. 17. Sands TA. Physics-based control methods. In: Advances in Spacecraft Systems and Orbit Determination. London, UK: InTech Publishers; 2012. pp. 29-54
  18. 18. Sands T. Improved magnetic levitation via online disturbance decoupling. Physics Journal. 2015;1:272-280
  19. 19. Sands T. Phase lag elimination at all frequencies for full state estimation of spacecraft attitude. Physics Journal. 2017;3(1):1-12

Written By

Brendon Smeresky and Alex Rizzo

Submitted: 18 May 2019 Reviewed: 17 October 2019 Published: 27 May 2020