Reference frames
Earth Centred Inertial (ECI) reference frame: The origin of these axes is in the Earth’s centre. The X axis is parallel to the line of nodes, which is the intersection between the Earth’s equatorial plane and the plane of the ecliptic, and is positive in the Vernal equinox direction (Aries point). The Z axis is defined as being parallel to the Earth’s Geographic north-south axis and pointing north. The Y axis completes the right-handed orthogonal triad.
Orbit reference frame: The origin of this orbit reference frame moves with the cm (centre of mass) of the satellite in the orbit. The Z axis points toward the cm of the earth. The X axis is in the plane of the orbit, perpendicular to the Z axis, in the direction of the velocity of the satellite. The Y axis is normal to the local plane of the orbit, and completes a three-axis right-hand orthogonal system. Satellite body reference frame: The origin of this reference frame is in the satellite centre of mass; the axes are assumed to coincide with the body’s principal inertial axes.
Spacecraft nonlinear attitude model
The attitude dynamic equations are obtained from Euler’s moment equation as follows.15
(1)
Where
, is angular velocity vector of satellite body reference frame with respect to inertial reference frame, expressed in satellite body reference frame, h is angular momentum vector of the entire system, expressed in satellite body system. h denotes differentiation of h in the body frame and T is the sum of external torques.
For a rigid satellite,
where I is the satellite inertia matrix expressed in the body frame, so the attitude dynamic equations reduce to well-known form
(2)
(3)
where
is the orbital angular rate, A(q) is the attitude matrix with respect to the orbital reference frame and
is angular velocity vector of orbit reference frame with respect to inertial reference frame, expressed in satellite body reference frame. For earth pointing satellite, we always consider the orbit reference frame as an attitude reference, so that
(4)
Where
, is angular velocity vector of satellite body reference frame with respect to orbit reference frame, expressed in satellite body reference frame. When the satellite has the desired attitude, the satellite body reference frame must remain aligned with orbit reference frame.
Linearised attitude dynamics model
The Laguerre MPC control algorithm requires a linearized dynamic model. It should be pointed out that in the derivation of the linearized attitude dynamics model, we assume a circular orbit for the satellite we also assume the inertia matrix is diagonal.
Besides quaternion method, attitude transformation matrix can be expressed with Euler angle
. The roll angle
is defined as a rotation about the x body axis, the pitch angle (θ) about the y body axis, and the yaw angle
about the z body axis. Assuming small variation of the Euler angles, the attitude transformation matrix becomes:
(6)
And one also obtains that:
So Eq. 4 becomes
(7)
With these assumptions in (6), (7) becomes
Finally, the satellite attitude dynamics are approximated well by a linear model.16
(9)
Where,
Where Td is disturbance torque which is considered as zero in this paper,
is control torque and
.
Magnetic attitude control
The controlling torque acting on spacecraft is produced by the interaction between a magnetic moment generated within a spacecraft and the earth’s magnetic field:
(10)
Where m is the generated magnetic moment inside the body and b is the earth’s magnetic field intensity.
Eq. 10 can be rewritten as,
(11)
A dipole approximation of the Earth’s magnetic field is given in the following equation expressed in orbit reference frame.9
(12)
Where im is the inclination of the satellite’s orbit with respect to the magnetic equator, and a is the orbit’s semi-major axis. Time is measured from t=0 at the ascending-node crossing of the magnetic equator. The field’s dipole strength is
The magnetic field in satellite body reference frame is given by
(13)
Constraints in magnetic attitude control
In Eq. 10, m must satisfy orthogonality conditions with respect to TC and b, so one must have,
(14)
Beside, constraints on the coils’ magnetic dipoles (actuators’ saturation) play an important role in the formulation of the magnetic attitude control problem. Such constraints are of the form
(15)
The magnetic dipole m is given by.6
(16)
Where,
(17)
So the constraints on coils’ magnetic dipoles can be translated into constraints on the control variable TC Using Eq. 17, it follows that
(18)
which in turn implies
(19)
Here the mathematic expressions and derivations of MPC algorithm are given. It should be pointed out that the idea of Laguerre MPC is proposed by Wang. In this thesis, however, we will be concerning on the Laguerre MPC.
The plant to be controlled is described by the discrete time model of the form as
(2.20)
Assume that the plant has p inputs, q outputs and n states. Let us denote the difference of the state variable by
(2.21)
And the difference of the control variable by
(2.22)
Then we augment the original state space model (2.21) and (2.22) as
(2.23)
Now we model the control signal by forward operators. Let us denote the vector
The cost function of Traditional MPC is expressed as
(2.24)
Where,
is a
identity matrix, RS is the set point vector,
is the weighting matrix for control signal, NC is control horizon, Npis prediction horizon. The triplet (A, B, C) is called the augmented model.
Now we calculate derivation of the cost function J:
(2.2.5)
The necessary condition of the minimum J is obtained
(2.2.6)
The optimal solution for the control signal is
(2.2.7)
Now we derive the close-form control law. Because of the receding horizon control principle, we only take the first element of
at time ki as the incremental control, thus
(2.28)
Where
is the first element of
and
is the first row of
. (2.28) is in a standard form of linear time-invariant state feedback control. The state feedback control gain vector is Kmpc. Therefore, with the augmented design model
The closed-loop system is obtained by substituting (2.28) into the augmented system equation; changing index ki to k, leading to the closed-loop equation
(2.29)
Thus we can see when constraints have not been taken in to consideration, the MPC control algorithm can be written as a closed-loop form. All parameters required in MPC control algorithm can be calculated off-line and the on-line computational demand is relatively low.
Laguerre MPC
Now we model the control signal with Laguerre functions. Laguerre functions are a set of discrete orthonormal basis functions that can be expressed as
(2.30)
(2.31)
Letting
denote the inverse z-transform of
The set of discrete-time Laguerre functions satisfies the following difference equation:
(2.32)
where the initial condition is given by
(2.33)
a is the Laguerre scaling factor,
, and A1 is a N×N matrix. For example N=5,
.
The Laguerre functions can be used to describe the impulse response of the stable system. If we consider the future control signals in model predictive control as the impulse response of a SISO system,
can be described as
(2.34)
where
For a MIMO system,
is given in following equation:
(2.35)
Where
is the current incremental control,
is the future incremental control at sample k and
represents the Laguerre network description for the ith control. The input matrix can be partitioned to
Then the cost function becomes
(2.36)
Where the matrix
and
are
Biis the ith column of the B matrix, Q and RL are weighting matrix,
is weighting matrix for state variables,
is a diagonal matrix (N × N) for control variables
.
The object of model predictive control is to solve an optimization problem that takes into account the constraints. Although model predictive control is able to deal with many kinds of constraints either on control signals or on output signals, here we will only focus on constraints on the Amplitude of the Control Variables. Optimization in MPC is realized by minimizing the object function subject to some constraints, which can be considered as a quadratic programming problem. The objective function J and the constraints in Quadratic Programming are expressed as
(2.37)
(2.38)
Where E, F, M and
are compatible matrices and vectors in the quadratic programming problem.
A simple algorithm called Hildreth’s Quadratic Programming was proposed to solve Quadratic Programming problem. The iteration expression of Hildreth’s Quadratic Programming Procedure is given in following equation:
(2.39)
Where
(2.40)
m means the mth iteration, the scalar
is the ijth element in the matrix
and ki is the ith element in the vector.
is a column vector called Lagrange multiplier. The number of its components is equal to the number of inequality equations for input constraints and
is the ith component of the Lagrange multiplier.
When the iteration is completed, the converged Lagrange multiplier
contains either zero or positive values. The constrained minimization over x is given by
(2.41)
As it can be seen from (2.40), the on-line computation demand of MPC is mainly determined by the size of matrix
. The size of matrix M is determined by the number of inequality equations, which can’t be changed; therefore the size of matrix E is the critical factor for decreasing the on-line computation requirement.
For traditional MPC, the cost function is given in (2.24). To perform optimization, we substitute the matrix E in (2.37) with matrix
. It should be noted that the size of matrix
is
and hence it can be concluded that the number factors involved in on-line computation is determined by the control horizon
. For some complex dynamic system,
has to be selected greater than 80 to stabilize the system, which will lead to a large computation demand.
For Laguerre MPC, the matrix E in (2.37) can be substituted by
, which is a
matrix. The number of factors involved in on-line computation is decided by the Parameter N. It should be noted that N can be a factor of
when the Laguerre scaling factor a is selected greater than zero, which means the factors involved in on-line computation will be decreased greatly when Laguerre functions are utilized in MPC design. If a is equal to zero, N has to be chosen to be equal to
and under this situation the Laguerre MPC becomes identical to traditional MPC. This is a very attractive property of Laguerre MPC because we can easily compare the performances of these two MPC algorithms by change the value of Laguerre scaling factor a
Different types of control applications require different implementation solutions. Most MPC applications target process control, in which sample periods are low and the plant is physically large, meaning that processing based upon an industrial computer is adoptable. However, the proposed electro-magnetic control system is targeting very small satellites, in which the controller hardware must be embedded. It may require very high sampling rate for precise attitude control. Also executing the MPC is relatively complex with heavy matrix operations. It is therefore requires some high performance device for control system processing.
SoC for satellite on-board data handling
There are two types of satellite on-board data handling systems: central and distributed. The central processing approach has one on-board computer to deal with all the data processing for each subsystem. The distributed processing approach, however, has many on-board computers. Some subsystems may have more than one processor. Nowadays most of the satellites adopt the distributed approach, but for nanosatellites this approach is not efficient due to the limited size and power. Hence, the SoC solution is proposed not only for attitude control but also for data processing for other subsystems.
The SoC can implement the whole digital functionality of the satellite on a single chip. The gate densities achieved in current FPGA devices have enough logic gates/elements to implement different functionalities on the same chip by mixing self-designed modules with third party ones. In the SoC, it contains dedicated processors for each subsystem. Figure 1 shows the SoC architecture. It contains a general purpose processor and the dedicated processors. Its structure comprises an AMBA17 compliant bus that communicates between the general purpose processor and the control system processor. Generally, the MPCSP is independent, but the general purpose processor as the controller of the SoC monitors the control state variables and satellite attitude information from the inertial sensors. These data are a part of telemetry information for satellite housekeeping.
Figure 1 Soc architecture for satellite OBDH.
MPCSP design and implementation
To map the control algorithm to processor architecture, it is divided into tasks or processes. These processes include data input and output (IO), data storage (Memories), timer, instruction fetching and decoding, next instruction address calculation (Program Counter) and arithmetic operations (ALU). This partitioning should allow all the processes to be mapped easily into hardware, minimizing the resources required.
The number of concurrent operations can determine the amount and functionality of the hardware structures. For example, the maximum number of simultaneous data transactions that required for arithmetic operations determines the number of ALU ports. Also, communication channels between the ALU, accumulator, memories and IO must be assigned with specific data bus.
The execution of the control algorithm requires the repeated execution of a set of instructions (program). Although the number of instructions in the control loop can be small in the case of implementing a simple controller, the overhead that manipulate the program counter maybe relatively large. We therefore must pay special attention to the architecture of the program counter that implements control loops. Thus, the MPCSP can provide a looping mechanism that introduces a short, or ideally zero, overhead.
The final step is to create a hardware model that supports the operations needed to implement the control algorithm. This hardware model is programmed using the hardware description language. The resulted MPCSP is simulated and verified by running the MPC algorithm with the application-specific instructions. The MPCSP is then synthesized floor planned and placed & routed. The final net list can be verified via being downloaded into the FPGA and running the hardware-in-loop simulation.
Figure 2 shows the MPCSP architecture. It adopts a simple mixed data format in 2’s complement: the coefficients are in 12-bit floating point format, with 6-bit for mantissa and 6-bit for exponent. The state variables and other data are in 32-bit fixed point format, with 16 integer bits and 16 fractional bits. The memories include program ROM, data ROM and data RAM for control program, coefficients and intermediate states respectively. The sample timer is used to determine the sample interval for each control loop. The program counter processes one instruction at each clock cycle. It will halt the operation at the end of the control program, and reset to the address where the control loop starts at the rising edge of the sample timer.
Figure 2 MPCSP architecture.
The MAC is the only processing element in the previous CSP design. Although this approach reduces the circuitry complexity, it is not efficient in terms of power and speed. Hence, in the MPCSP design, several processing elements are adopted for arithmetic operations as shown in Table 1. Each instruction uses the standard RISC convention of 32-bit fixed-length. All instructions have a single clock cycle execution.
Op code |
Name |
Function Description |
0 |
HLT |
No Operation |
1 |
RDW |
Read data from data ROM |
10 |
WRW |
Write data to data RAM |
11 |
OUT |
Output the control signals |
100 |
MUL |
Multiply |
101 |
ADD |
add |
110 |
SUB |
subtract |
111 |
INV |
invert |
1000 |
SET |
Set the sampling frequency |
1xx1 |
WPC |
Set the star value for the program counter |
Table 1 MPCSP instructions
The IO block has 12 inputs and 4 PWM outputs. The inputs are connected to the inertial sensors, including accelerometers, gyroscopes, magnetometers and sun sensors. The outputs are connected to the magnet coils through the power amplifiers. For attitude control, 3 magnet coils are needed to provide three-axis actuation.
The data bus and address bus of the MPCSP are connected to the AMBA to allow the general-purpose processor collect house-keeping data. The MPCSP is implemented targeting the Xilinx Virtex-4 FX100 FPGA technology. The MPCSP occupies less than 8% of the FPGA total area. It runs up to 120MHz. The power consumption is around 183 mW.