1 Introduction

The growing interest in space exploration is focusing the research in the development of space architectures able to be independent and self-sustainable. Nowadays, space missions for satellites require the capability to rapidly change the attitude with high slew rate, both to ensure the success of the mission and to avoid catastrophic impacts among crafts (Yadlin 2011; Courie et al. 2018). In general the attitude control can be defined as the process aimed to stabilize and adjust the orientation of spacecraft during space maneuvers (National Academies of Sciences and Medicine 2016). Precise attitude tracking control of small satellites is a demanding task due to the limited hardware resources of sensors, actuators, and processors equipped on-board. During the years, attitude control systems based on Control Moment Gyros (CMGs) have been used for a large scale of satellites as they can generate a large torque compared to Reaction Wheels (RWs) systems. Though CMG systems can provide rapid slew capability and high pointing accuracy not using any of the limited propellant dedicated to the main propulsion system, an important difficulty is their inherent geometric singularity problem, regardless of how many CMGs the system is equipped with. Various efforts have been made to overcome this troublesome problem, and many CMG singularity avoidance methods have been developed, with different advantages and disadvantages (Kraft 1993; Wie 2005; Lee et al. 2007; Chakravorty 2012).

A configuration with CMGs and steering scheme for rapid maneuvering of Earth observation satellites is presented in paper (Yadlin 2011). The CMG singularity arises when the torque vectors of all the CMGs are aligned on a plane, so that the CMG system cannot produce a control torque in the normal direction of that plane. Different configurations of CMGs systems are compared in Miceli (2007), using a single PID controller with a steering law based on the Moore-Penrose inverse matrix to avoid the singularity condition. The analysis is particularly interesting for the comparison among different actuator system: the first two are CMG systems in pyramidal configuration with a different skew angles, the third system is a cluster of two CMGs and four RWs.

Even if Proportional Integral Derivative (PID)-based controllers are largely used in industrial applications, they are used in cases where the plant has a simple dynamics and where an appropriate proportional and damping gains are able to ensure a stable behavior of the control system. These controllers, combined with a Singular Direction Avoidance (SDA) steering law (Ford and Hall 2000), are usually designed for CMG-based space systems, as in Xin et al. (2015); Bedrossian et al. (2005), Ciavola et al. (2019). However, if the system to be controlled is more complex, the implementation of an optimal control strategy could be better. The optimal control solution is easy and simple to design, and the feedback gains can be computed by solving a Riccati equation. The most successful methodology among the optimal control environment is the Model Predictive Control (MPC).

As clear from literature (Wang and Boyd 2009; Mayne 2014; Mammarella et al. 2018), however, one of the main drawback of the MPC control scheme is related to the online optimization problem and to the difficulty of embedding a real-time solver for the on-board implementation. A practical solution, usually used for MPC implementation on embedded systems, is the offline evaluation of the control law, uploaded on-board by means of lookup tables Bemporad et al. (2002). In literature, gain scheduling design are usually proposed for linear time-varying (LTV) system, but for spacecraft control using CMGs there is a limitation due to the high number of independent time-varying variables. So, gain scheduling design can be unfeasible. Moreover, in space applications, to handle uncertainties and fast changes on the dynamics, this solution is usually not adopted. For this reason, the real-time implementation (translated in a real-time solver) is a key aspect for the on-board implementation of an MPC control system.

MPC was first applied successfully for plants with slow dynamics (Qin and Badgwell 2003; Yu-Geng et al. 2013). However, in the last years, it was widely applied to different areas, as space applications. Indeed, only few control methodologies are able to address challenging tasks, required by space observations and missions, as deeply explained in Eren et al. (2017). The main advantages of using MPC controllers are related to two main aspects: (1) the MPC controller can directly calculate the angular velocity of the gimbals without calculating the external control torque, (2) input, state and hardware constraints can be included in the implementation. The first aspect enables us to avoid using the conventional steering laws with the singularity problem to drive the CMG system. Besides, the second aspect guarantees computational feasibility, secure operation, and the best possible performance of the system. As a consequence, the stability of the closed-loop system and its feasibility are guaranteed, while even the tracking performance is improved under the constraints.

In Guiggiani et al. (2015) a Model Predictive Controller for spacecraft attitude tracking with RWs actuators is proposed and the controller is designed for desaturation of the RWs, without fuel consumption, compensating the gravity gradient torques. In paper Ashok et al. (2016) the problem of attitude control of spacecraft using CMGs in pyramidal configuration is faced with the implementation of a method to avoid the singularity condition by means of Nonlinear MPC (NMPC). A singularity avoidance term is introduced in the cost function to be minimized, in order to generate a control input that moves away from the singularity when the CMG system approaches the neighbourhood of the singularity, and to rapidly converge to a desired attitude when the CMG system stays away from the singularity. Even if the implementation of an NMPC is treated, this paper still uses a steering law to calculate the value of the gimbal angular velocities. When a steering law is included in the closed-loop scheme, the controller generates the input and the steering law generates the gimbal rates value, avoiding the singularity condition, separately. So, it should happen that the generated torque differs from the controller torque, compromising the control performance in avoiding singularity. This problem can be resolved by generating directly from the controller the control input that does not achieve singularity.

In light of these circumstances, this paper proposes an MPC based attitude controller for the CMG system, which directly generates the gimbal rates so as to avoid the singularity problem possibly caused by the steering laws. The proposed method is based on an MPC method with additional features in Wada and Tsurushima (2016), which are virtual reference state and integrator state. Although the literature provides a linear MPC controller, it optimizes not only a sequence of control inputs, but also a virtual reference signal and an integrator state. These additional optimizations improve attitude tracking performance and reduce the steady-state error with the guarantee of recursive feasibility and constraints satisfaction. The further contribution of this paper is to verify the real-time implementability of the proposed MPC controller using an experimental testbed with four CMGs in pyramidal configuration. By floating the experimental equipment via spherical air bearing and by matching the center of rotation and the center of gravity of the equipment, the testbed simulates spacecraft attitude dynamics. Since ground experiments of spacecraft attitude control are very difficult, and furthermore MPC controllers require implementation of real-time optimization, there have been a few references, which conduct experimental verification of MPC based spacecraft attitude control. We demonstrate both simulation and experimental results of the proposed method, and also show an optimization solver, which is easy to be translated and computationally efficient for on-board implementation.

The paper is organized as follows. In Sect. 2 the dynamics of the analyzed system is considered, focusing on attitude dynamics. The testbed system is described in Sect. 2.2. The MPC controller is introduced in Sect. 3, including the virtual reference and the integrator state. The real-time implementability of the proposed MPC controller is also discussed in Sect. 3.1. The Simulation results are described in Sect. 4 and the experimental test in Sect. 5. Finally, conclusions are drawn in Sect. 6.

2 Preliminaries

Some preliminaries on Linear Matrix Inequalities (LMIs) and on MPC control system are first introduced. The LMI approach is used for the definition of the controller gains and the Yalmip Matlab toolbox Lofberg (2004) is considered.

Given the symmetric matrices \(F_{i}=F_{i}^{T}\in {\mathbb {R}}^{n\times n}\), with \(i=0,\dots ,m\), a LMI problem has the form

$$\begin{aligned} F(x)\triangleq F_{0}+\sum _{i=1}^{m}x_{i}F_{i}>0 \end{aligned}$$
(1)

where \(x\in {\mathbb {R}}^{m}\). The inequality symbol in Eq. (1) means that F(x) is positive definite, i.e. \(u^{T}F(x)u>0\) for all nonzero \(u\in {\mathbb {R}}^{n}\). This LMI is equivalent to a set of n polynomial inequalities in x.

Moreover, it is possible to find nonstrict LMIs, with the form

$$\begin{aligned} F(x)\ge 0 \end{aligned}$$
(2)

The LMI problem in Eq. (1) is a convex constraint on x and the set \(\{x|F(x)>0\}\) is convex indeed. Multiple LMIs such as \(F^{(1)}(x)>0,\dots ,F^{(p)}(x)>0\) can be expressed as the single LMI diag\((F^{(1)}(x),\dots ,F^{(p)}(x))>0\), where \(\mathbf{diag}\) denotes a diagonal matrix composed by the elements.

Whether the matrices \(F_{i}\) are diagonal, the LMI \(F(x)>0\) is just a set of linear inequalities. Nonlinear convex inequalities are represented as an LMI problem using Schur complements.

$$\begin{aligned} \begin{bmatrix} Q(x) &{} S(x)\\ S(x)^{T} &{} R(x) \end{bmatrix} >0 , \end{aligned}$$
(3)

where \(Q(x)=Q(x)^{T}\), \(R(x)=R(x)^{T}\) and S(x) depend affinely on x, is equivalent to

$$\begin{aligned} R(x)>0, \qquad Q(x)-S(x)R(x)^{-1}S(x)^{T}>0 \end{aligned}$$
(4)

It is often possible to deal with problems in which the variables are matrices as follows

$$\begin{aligned} A^{T}P+PA<0 \end{aligned}$$
(5)

where \(A\in {\mathbb {R}}^{n\times n}\) is given and \(P=P^{T}\) is the variable. We can put the Lyapunov inequality in Eq. (5) in the form of Eq. (1) considering \(P_{1},\dots ,P_{m}\) as a basis for symmetric \(n\times n\) matrices \((m=n(n+1)/2)\) and then taking \(F_{0}=0\) and \(F_{i}=-A^{T}P_{i}-P_{i}A\). Furthermore, leaving LMI inequalities in a condensed form as Eq. (5) may lead to more efficient computation.

Consider the quadratic matrix inequality

$$\begin{aligned} A^{T}P+PA+PBR^{-1}B^{T}P+Q<0 , \end{aligned}$$
(6)

where A, B, \(Q=Q^{T}\), \(R=R^{T}>0\) are given matrices of appropriate sizes and \(P=P^{T}\) is the variable. It can be expressed as the LMI problem

$$\begin{aligned} \begin{bmatrix} -A^{T}P-PA-Q &{} PB\\ B^{T}P &{} R \end{bmatrix}>0 \end{aligned}$$
(7)

This representation shows that the quadratic matrix inequality in Eq. (7) is convex in P.

In some problems it is possible to find linear equality constraints on the variables such as

$$\begin{aligned} P>0, \quad A^{T}P+PA<0, \quad \text{ Tr }P=1 \end{aligned}$$
(8)

where \(P\in {\mathbb {R}}^{k\times k}\) is the variable. In order to write Eq. (8) in the form \(F(x)>0\) we can eliminate the equality constraint considering \(P_{1},\dots ,P_{m}\) as a basis for symmetric \(k\times k\) matrices with trace zero \((m=(k(k+1)/2)-1)\) and \(P_{0}\) as a symmetric \(k\times k\) matrix with Tr\(P_{0}=1\). Thus, \(F_{0}=\text{ diag }(P_{0},-A^{T}P_{0}-P_{0}A)\) and \(F_{i}=\text{ diag }(P_{i},-A^{T}P_{i}-P_{i}A)\), for \(i=1,\dots ,m\), should be used in the analysis. The LMIs defined in this paper are solved with the Matlab Toolbox Yalmip Lofberg (2004).

3 Model definition

As briefly introduced before, the main objective of this paper is the precise attitude control of a testbed, equipped with four Control Moment Gyros (CMGs) in pyramidal configuration. The testbed is considered as a rigid body, in which Euler’s equation and quaternion kinematics are included Markley and Crassidis (2014). After the definition of the dynamic and kinematic equations of the testbed, the Linear Time-Invariant (LTI) mathematical model is derived in a state space formulation.

3.1 Attitude dynamics modeling

For the study of spacecraft dynamics, two reference frames are usually considered: an Inertial Reference Frame and a Body Reference Frame, as in Fig. 1.

Fig. 1
figure 1

Earth-Centered Inertial Reference Frame and Body Reference Frame

The Inertial Reference Frame considered in this study is the Earth-Centered Inertial (ECI) that is also called Inertial Geocentric Reference Frame (Fig. 1). It is commonly used to study the motion of a body orbiting around Earth and it has its origin in the Center-of-Mass (CoM) of Earth.

The Body Reference Frame (Fig. 2) has been adopted to describe the attitude dynamics once introduced the CMGs to the equations of motion. The origin of the Body Reference Frame is in the CoM of the spacecraft and it is rigidly attached to the body.

Fig. 2
figure 2

Configuration of a pyramidal testbed equipped with 4 CMGs

Taking into account the previous assumption, the Euler’s equation of motion can be written as Srinivasan et al. (2014)

$$\begin{aligned} M_B={\dot{h}}_B+\omega _B\times h_B , \end{aligned}$$
(9)

where the subscript \(_B\) indicates variables in the Body Reference Frame, \(\omega _B \in {\mathbb {R}}^{3}\) is the angular velocity of the spacecraft, \(h_B \in {\mathbb {R}}^{3}\) is the angular momentum, \(M_B \in {\mathbb {R}}^{3}\) is the torque vector defined as

$$\begin{aligned} M_B=\sum ^{n}_{i=1}r_i \times F_i . \end{aligned}$$

\(F_i\) is the force which has a momentum with respect to the CoM, and \(r_i\) is the distance between the CoM and the considered force. For a generic body, the inertia tensor \(\mathrm {J}\) directly relates the angular velocity with the angular momentum. The angular momentum h of a rigid body, referred to its CoM, can be defined

$$\begin{aligned} h=\mathrm {J}\omega . \end{aligned}$$
(10)

Considering the testbed system, Eq. (10) can be rewritten as

$$\begin{aligned} h_B=\mathrm {J}_B \omega _B+h_B^C . \end{aligned}$$
(11)

Thus, the total angular momentum is the sum of two terms: (1) the angular momentum of the spacecraft, and (2) \(h_B^C\) is the term given by CMG system, which for a pyramidal configuration is

$$\begin{aligned} h_B^C=h_{\omega } \sum _{i=4}^4 \overline{h_i}(\theta _i) , \end{aligned}$$
(12)

with

$$\begin{aligned}&\overline{h_1}(\theta _1)= \begin{bmatrix} -\sin (\theta _1)\cos \beta \\ \cos (\theta _1) \\ \sin (\theta _1)\sin \beta \end{bmatrix},~~~ \overline{h_2}(\theta _2)= \begin{bmatrix} -\cos (\theta _2) \\ -\sin (\theta _2)\cos \beta \\ \sin (\theta _2)\sin \beta \end{bmatrix}, \end{aligned}$$
(13)
$$\begin{aligned}&\overline{h_3}(\theta _3)= \begin{bmatrix} \sin (\theta _3)\cos \beta \\ -\cos (\theta _3) \\ \sin (\theta _3)\sin \beta \end{bmatrix},~~~ \overline{h_4}(\theta _4)= \begin{bmatrix} \cos (\theta _4) \\ \sin (\theta _4)\cos \beta \\ \sin (\theta _4)\sin \beta \end{bmatrix}, \end{aligned}$$
(14)

where \(\theta _i \in {\mathbb {R}}^4\) is the gimbal angle, for \(i=1,...,4\)., and \(h_{\omega }=\mathrm {J}_{\omega }\omega _{\omega } \in {\mathbb {R}}\) denotes the angular momentum of each wheel. Since we suppose four identical wheels rotating at the same constant speed, \(h_{\omega }\) is a constant scalar.

Combining the previous equations, the Euler’s equation here considered is

$$\begin{aligned} M_B= \omega _B \times (\mathrm {J}_B\omega _B+h_B^C)+\mathrm {J}_B {\dot{\omega }}_B+{\dot{h}}_B^C . \end{aligned}$$
(15)

For a cluster of 4 CMGs, the internal angular momentum vector \(h_B^C\) is a non linear function of the gimbal angles \(\theta _i\), with \(i=1,...,4\), of each CMG, as in Eq. (12). The time derivative of Eq. (12) is

$$\begin{aligned} {\dot{h}}_B^C=h_{\omega }A(\theta ){\dot{\theta }} , \end{aligned}$$
(16)

where the matrix \(A(\theta )\in {\mathbb {R}}^{3\times 4}\), considering a fixed skew angle \(\beta\), is

$$\begin{aligned} A(\theta )=\left[ \begin{array}{cccc} -\cos (\theta _1)\cos \beta &{} \sin (\theta _2) &{} \cos (\theta _3)\cos \beta &{} -\sin (\theta _4) \\ -\sin (\theta _1) &{} -\cos (\theta _2)\cos \beta &{} \sin (\theta _3) &{} \cos (\theta _4)\cos \beta \\ \cos (\theta _1)\sin \beta &{} \cos (\theta _2)\sin \beta &{} \cos (\theta _3)\sin \beta &{} \cos (\theta _4)\sin \beta \end{array} \right] . \end{aligned}$$
(17)

The columns of matrix \(A(\theta )\) express the contribution of each CMG to \({\dot{h}}_B^C\). Finally, the following assumptions are considered

  1. 1.

    The initial angular momentum is zero, and consequently \(\omega _B(0)=0\)

  2. 2.

    The initial torque applied to the body is zero, \(M_B(0)=0\)

With these hypotheses, starting from Eq. (15) and substituting Eq. (16), we can easily obtain the following simplified equation for the angular acceleration

$$\begin{aligned} {\dot{\omega }}_B=-h_{\omega }\mathrm {J}_B^{-1}A(\theta ){\dot{\theta }} . \end{aligned}$$
(18)

This latter equation relates the angular acceleration of the testbed to the angular rate of the gimbals \({\dot{\theta }}\), which is the control input vector in this system. For the definition of the model, the subscript that indicates the Body Reference Frame is omitted for simplicity.

The kinematic equation of the system using a quaternion representation is

$$\begin{aligned} {\dot{q}}=\frac{1}{2}\varSigma (q)\omega , \end{aligned}$$
(19)

with \(q=[q_v^T,q_4]^T=[q_1,q_2,q_3,q_4]^T \in {\mathbb {R}}^4\), where \(q_v= [q_1,q_2,q_3]^T \in {\mathbb {R}}^{3}\) is the vectorial part of the quaternion, and \(q_4\) is the scalar term.

The matrix \(\varSigma (q) \in {\mathbb {R}}^{4\times 3}\) is defined as:

$$\begin{aligned} \varSigma (q)=\left[ \begin{array}{ccc} q_4 &{} -q_3 &{} q_2 \\ q_3 &{} q_4 &{} -q_1 \\ -q_2 &{} q_1 &{} q_4 \\ -q_1 &{} -q_2 &{} -q_3 \\ \end{array} \right] . \end{aligned}$$

Combining Eqs. (18) and (19) obtained previously, the following mathematical model can be obtained

$$\begin{aligned} \displaystyle {{\dot{x}}_p=\left[ \begin{array}{c} {\dot{q}} \\ \\ {\dot{\omega }} \end{array} \right] = \left[ \begin{array}{c} \frac{1}{2}\varSigma (q)\omega \\ \\ -h_{\omega }\mathrm {J}^{-1}A(\theta ){\dot{\theta }} \end{array} \right] ,} \end{aligned}$$
(20)

where the system state vector is defined \(x_p=\left[ \begin{array}{c} q \\ \omega \end{array} \right] \in {\mathbb {R}}^{n_p}\), with \(n_p=7\).

Rearranging the previous equation, the state equation of the system is

$$\begin{aligned} {\dot{x}}_p=\left[ \begin{array}{cc} 0_{4\times 4} &{} \frac{1}{2}\varSigma (q) \\ \\ 0_{3\times 4} &{} 0_{3\times 3} \end{array} \right]\,x_p + \left[ \begin{array}{c} 0_{4\times 4} \\ \\ -h_{\omega }\mathrm {J}^{-1}A(\theta ) \end{array} \right]\,{\dot{\theta }}={\bar{A}}_p(x_p) x_p+{\bar{B}}_p(\theta ){\dot{\theta }} \end{aligned}$$
(21)

The state of the system is \(x_p \in {\mathbb {R}}^7\) and the control input is \({\dot{\theta }} \in {\mathbb {R}}^4\), that is the angular rates of the gimbals. The matrix \({\bar{B}}_p\) can be considered to be a (external) parameter-dependent matrix as \({\bar{B}}(\theta )\).

A linearisation is performed assuming that the initial gimbal angles are \(\theta _0=[0,0,0,0]^T\). This fixed value is used to evaluate the matrix \(A(\theta )\), so the matrix \({\bar{B}}_p\) is constant. The desired attitude in terms of \(\omega _d\) and \(q_d=[q_{1,d},q_{2,d},q_{3,d},q_{4,d}]^T\) is considered as equilibrium point, to have a constant state matrix. We linearize \({\bar{A}}_p\) matrix around the terminal value of the desired attitude. Thus, more precisely, the constant matrix \({\bar{A}}_p(q_d(T))\) is used, where “T” denotes the terminal time.

So, we have

$$\begin{aligned} {\dot{x}}_p=\left[ \begin{array}{cc} 0_{4\times 4} &{} \frac{1}{2}\varSigma (q_d(T)) \\ \\ 0_{3\times 4} &{} 0_{3\times 3} \end{array} \right]\,x_p + \left[ \begin{array}{c} 0_{4\times 4} \\ \\ -h_{\omega }\mathrm {J}^{-1}A(\theta _0) \end{array} \right]\,{\dot{\theta }} , \end{aligned}$$
(22)

with the following output equation

$$\begin{aligned} y= \left[ \begin{array}{cc} I_3 &{} 0_{3\times 4} \\ \\ 0_{3\times 4} &{} I_3 \end{array} \right]\,x_p={\bar{C}}_p x_p , \end{aligned}$$
(23)

where \(y=[q_v^T,\omega ^T]^T \in {\mathbb {R}}^6\) and \(I_3 \in {\mathbb {R}}^{3\times 3}\) is the identity matrix.

3.2 Testbed description

The testbed considered in this work is the one developed in Higashiyama et al. (2020), which is depicted in Fig. 3. Physical parameters of the testbed is summarized in Table 1. The testbed simulates a spacecraft using a metal plate equipped with the four CMGs in pyramidal configuration, a PC, two microcomputers, and three sets of counter weights. The metal plate is floated by compressed air via spherical air bearing, and the center of rotation and the center of gravity of the testbed is matched by manually adjusting the counter weights. The attitude and the angular velocity are estimated via a triaxial gyroscope and accelerometer called the 3-Space Sensor made by YEI Technology, and a low-pass filter. Moreover, the nominal moment of inertia is estimated by applying the least-square method to a regressor representation of the Euler’s equations of the uncontrolled rotational motion.

Fig. 3
figure 3

Testbed with 4 CMGs in pyramidal configuration

Table 1 Physical parameters of the testbed

4 Design of an MPC controller

Starting from the research of Wada and Tsurushima (2016), a linear MPC with integrator as a servo compensator is considered to control the attitude of a spacecraft/testbed. The integrator is included to reduce the steady-state error. From the optimization procedure, instead of only the control input, a virtual reference signal and an integrator state are also evaluated. The virtual reference signal w is a variable that substitutes the original reference signal r in the control algorithm in order to guarantee input constraints satisfaction. The controller has to decide at each sample time if the integrator state \(x_c\) must be optimized or not. If \(x_c\) is not optimized, it evolves according to the integrator equations in order to guarantee the steady-state error elimination. Instead, if \(x_c\) is included in the optimization problem, the optimized value of this variable gives a rapid decrease of the cost function value.

The plant system is described in the following state space formulation

$$\begin{aligned} x_p(k+i+1|k)=A_px_p(k+i|k)+B_pu(k+i|k) \end{aligned}$$
(24)
$$\begin{aligned} y(k+i|k)=C_px_p(k+i|k)+D_pu(k+i|k) , \end{aligned}$$
(25)

where \(x_p \in {\mathbb {R}}^{n_p}\) is the state of the plant, \(u \in {\mathbb {R}}^{m}\) is the control input and \(y \in {\mathbb {R}}^{n_y}\) is the system output. In our case the matrix \(D_p\) is null. In the MPC control system, the matrices of Eq. 21 are translated in discrete time as follows \(A_p := I_d + {\bar{A}}_pdt\), and \(B_p := {\bar{B}}_pdt\). \({\bar{C}}_p = C_p\). Moreover, following the literature, \((\cdot )(m|k)\) means a value at time m calculated at time k.

In our MPC formulation, both input and state constraints are considered as follows:

$$\begin{aligned}&\varPsi _uu(k+i|k) \le \theta _u,\ \ \ \forall i \ge 0 \end{aligned}$$
(26)
$$\begin{aligned}&\varPsi _{x_p}x_p(k+i+1|k) \le \theta _{x},\ \ \ \forall i \ge 0 , \end{aligned}$$
(27)

where the matrices \(\varPsi _u \in {\mathbb {R}}^{2m\times m}\), \(\theta _u \in {\mathbb {R}}^{2m}\), \(\theta _{x} \in {\mathbb {R}}^{2n_p}\) and \(\varPsi _{x_p} \in {\mathbb {R}}^{2n_p \times n_p}\).

Finally, the integrator equations are

$$\begin{aligned} x_c(k+i+1|k)= & {} x_c(k+i|k)+e(k+i|k) \end{aligned}$$
(28)
$$\begin{aligned} e(k+i|k)= & {} w(k|k)-y(k+i|k), \end{aligned}$$
(29)

with \(e \in {\mathbb {R}}^{n_y}\).

Combining the equations of the plant and the integrator, the error dynamics is defined as

$$\begin{aligned} \xi (k+i+1|k)= & {} A\xi (k+i|k)+B\nu (k+i|k) \end{aligned}$$
(30)
$$\begin{aligned} e(k+i|k)= & {} C\xi (k+i|k) , \end{aligned}$$
(31)

where

$$\begin{aligned} \xi (k+i|k)= & {} x(k+i|k)-\varPi w(k|k) \end{aligned}$$
(32)
$$\begin{aligned} \nu (k+i|k)= & {} u(k+i|k)-\varGamma w(k|k) \end{aligned}$$
(33)

and \(x=[x_p^T,x_c^T]^T\), \(C=[-C_p,0]\),

$$\begin{aligned} A=\left[ \begin{array}{cc} A_p &{} 0 \\ -C_p &{} I \end{array} \right] , \ \ \ B=\left[ \begin{array}{c} B_p \\ 0 \end{array} \right] \end{aligned}$$

The matrices \(\varPi\) and \(\varGamma\) are calculated for the tracking control problem in case of linear systems, and to guarantee input and state constraints satisfaction. The calculation procedure and the proofs are presented in Wada and Tsurushima (2016).

In this paper, the following cost function is considered and implemented

$$\begin{aligned} J(k) &=\sum _{i=0}^{H_s-1}\{||\xi (k+i+1|k)||^{2}_Q + ||\nu (k+i|k)||^{2}_R\} \nonumber \\ & +||\xi (k+H_s|k)||^{2}_P+||\varPi (w(k|k)-r(k|k))||^2_M , \end{aligned}$$
(34)

where \(H_s\) denotes the prediction horizon, and for a generic vector x and a square matrix A of appropriate dimension, \(||.||_A\) denotes the weighted Euclidean norm, namely, \(||x||_A:=(x^T Ax)^{1/2}\). The matrices Q, R, M, and P in (34) are positive-definite. The first three matrices are design matrices, while the matrix P has to be obtained solving an LMI problem for the terminal controller of the dual-mode MPC guaranteeing recursive feasibility and stability, as described in Wada and Tsurushima (2016).

The novelty in the defined cost function is found out in the last term, \(||\varPi (w(k|k)-r(k|k))||^2_M\) to include the virtual reference signal w into the optimization procedure. The virtual reference changes from the original reference r in order to satisfy the constraints and to obtain better control performance. The last term prevents w from being unnecessarily away from r, and also guarantees that the deviation between w and r remains finite. Under the regulator condition relating to the existence of the matrices \(\varPi\) and \(\varGamma\), the convergence of w to a step reference r is shown in Wada and Tsurushima (2016).

Using the prediction matrices S and T, the state prediction of the error system up to the horizon \(H_s\) is defined as

$$\begin{aligned} {\widetilde{\xi }}=T\xi (k|k)+S{\widetilde{\nu }} , \end{aligned}$$
(35)

where

$$\begin{aligned} {\widetilde{\xi }}=\left[ \begin{array}{c} \xi (k+1|k) \\ \vdots \\ \xi (k+H_s|k) \end{array} \right] \ \ \ \ \mathrm {and} \ \ \ \ {\widetilde{\nu }}=\left[ \begin{array}{c} \nu (k|k) \\ \vdots \\ \nu (k+H_s-1|k) \end{array} \right] . \end{aligned}$$

\({\widetilde{\xi }}\) is the vector of the future state, instead \({\widetilde{\nu }}\) is the optimized vector of the error system inputs, obtained by the optimization procedure.

Now it is necessary to rewrite the constraints in function of the variables of the error system. The input constraints must be rewritten, considering \(0\le i\le H_s-1\), as

$$\begin{aligned} {\widetilde{\varPsi }}_u({\widetilde{\nu }}+{\widetilde{\varGamma }}w(k|k)) \le {\widetilde{\theta }}_u , \end{aligned}$$
(36)

where \({\widetilde{\varPsi }}_u=\mathbf{diag} [\varPsi _u,\cdots ,\varPsi _u]\), \({\widetilde{\theta }}_u=[\theta _u^T,\ldots ,\theta _u^T]^T\) and \({\widetilde{\varGamma }}=[\varGamma ^T,\ldots ,\varGamma ^T]^T\).

The state constraints are rewritten as

$$\begin{aligned} {\widetilde{\varPsi }}_x(T\xi (k|k)+S{\widetilde{\nu }}+{\widetilde{\varPi }}w(k|k)) \le {\widetilde{\theta }}_x . \end{aligned}$$
(37)

\({\widetilde{\varPsi }}_x=\mathbf{diag} [\varPsi _x,\cdots ,\varPsi _x]\), \({\widetilde{\theta }}_x=[\theta _x^T,\ldots ,\theta _x^T]^T\) and \({\widetilde{\varPi }}=[\varPi ^T,\ldots ,\varPi ^T]^T\).

As already said, in the considered MPC, the integrator state can be or not optimized. In order to decide if \(x_c\) has to be optimized or not, a threshold \(\eta _s\) must be defined. The integrator state \(x_c\) is reset at each sampling time so that the cost function value J(k) is minimized while J(k) is greater then \(\eta _s\). The control algorithm with integral action is used to achieve zero steady-state error when J(k) is less than or equal to \(\eta _s\).

The value of \(\eta _s\) is determined by trial and error procedure. If \(\eta _s = 0\), the robustness against the disturbances cannot be assured. However, if \(\eta _s\) is too large, the robustness against disturbances is improved but the tracking performance are not good. So, the parameter \(\eta _s\) has to be chosen by considering a trade-off between tracking performance and robustness against disturbances.

4.1 Real-time implementability

For the implementation of the MPC control system, the required resources are correlated with the problem size (i.e., number of constraints, prediction horizon) and, at the same time, the efficiency of the solver algorithm for the optimization of the cost function. In addition to these two computational indices, on-board hardware capabilities and software architectures should also be considered. Implementation issues are discussed in this Section due to hardware constraints and limited computational power of the embedded controller. Some simplifications of the code and analysis of the solvers are required. Moreover, since the GNC hardware is tested on Matlab/Simulink environment, the selection criteria for the solver includes compatibility with this environment. In this paper, in implementing the proposed controller to the testbed, we equivalently convert the optimization problem formulated as an LMI optimization problem in Wada and Tsurushima (2016) into a quadratic programming problem, which has much less computational burden, as

$$\begin{aligned} \min _{\psi } \frac{1}{2}\psi (k)^TH\psi (k) + f^T\psi (k) \ \ \ \ \mathrm {subject \ to:} \ \ A_{con}\psi \le B_{con} \end{aligned}$$

where \(\psi (k)\) is the optimized vector.

Moreover, the cost function is re-written using Matlab notation, to simplify the implementations on this environment. So, we have

$$\begin{aligned} \min _{\psi } \frac{1}{2}\psi (k)^TH\psi (k) + \phi (k)^TF\psi (k) + \frac{1}{2}\phi (k)^TY\phi (k) \ \ \ \ \mathrm {subject \ to:} \ \ A_{con}\psi \le B_{con} \end{aligned}$$

where \(\phi (k)\) is a vector composed by the measured state of the system and by the reference signals.

The tested solvers are

  • quadprog, the interior-point-convex algorithm provided by the Matlab Optimization Toolbox to solve quadratic programming problem,

  • fmincon, Matlab function that can implement four different algorithms: interior-point, Sequential Quadratic Programming (SQP), active set, and thrust-region-reflective. Also this solver deals quadratic programming problems.

  • quadwright, a quadratic programming solver developed by J. Currie presented in Currie (2014); Wright (1996), able to speed up the computational capabilities for embedded applications.

All these solvers are tested in simulations. The software quadprog can use a thrust-region-reflective method for handling problems with bounds and linear equality constraints. However, it showed an high computational effort and cannot be translated in C code. The solver fmincon is usually used for nonlinear constrained problems and it finds a constrained minimum of a scalar function of several variables starting at an initial estimate. This solution is not a global minimum, but it is computational efficient. Finally, the quadwright provides the smallest computational times, because it has been developed with a focus on efficient memory use and high speed convergence. For the experimental verification, we create a C++ code with Eigen and eiquadprog libraries. The Eigen library is a C++ template library for linear algebra, and the eiquadprog Guennebaud et al. (2011) library is a C++ routine working with Eigen data structures for solving quadratic programming problems based on the Goldfarb-Idnani active-set dual method.

5 Simulation results

The simulations are performed in Matlab, with an Intel Core i7 at 2.4GHz and 8GB RAM. The selected sampling time is 25 ms and the prediction horizon \(H_s\) is 5 steps. The MPC solver, as previously said, is quadwright. The controller parameters are defined in Table 2.

Table 2 MPC Controller Parameters

The reference signals for the quaternion are evaluated from the evolution of the angular velocity, starting from Eq. (19), for all different simulation cases. Furthermore, in all the simulations the initial conditions are null states x, except for \(x_4(0) = q_4 = 1\) and null gimbal angles \(\theta\). So, the initial conditions are the ideal quaternion and null angular velocities. Two set of simulations are considered: (1) in the first set of simulations, all the three angular velocities are changed. Trapezoidal variations of the angular velocities are simulated, (2) in the second set of simulations, triangular variations of an angular velocity is examined.

5.1 First set of simulations

All the simulations are performed for both of the linear classical MPC and the MPC with optimization of virtual reference signal and integrator state in order to compare their control performance. Here, all the three angular velocities are changed. A simulation time of 20 seconds is considered. The desired angular velocities in the first simulation are \(\omega _d = [7,3,1]^T\) deg/s. The desired quaternion are evaluated from Eq. (19). Comparing Figures 5, 6 and 7, it is clear that MPC with optimization of integrator state and virtual reference has better performance with respect to the classical MPC, even if all the angular velocities are changed. Moreover, a noisy input is obtained by the classical MPC as in Figure 8. The control input of the MPC with integrator state and virtual reference is shown in Figure 9. In a similar way, noisy variation of the gimbal angles can be observed in Figure 10, whereas no noisy response is observed in Figure 11. Instead, no difference can be observed in the quaternion behavior, as in Figures 4, 5 and 6. Finally, to show the effectiveness of the proposed controller, a singularity index is evaluated, which is det\((AA^T)\), as in Higashiyama et al. (2020). Highest is the singularity index, more effective is the singularity avoidance. The singularity indices are in Figures 12 and 13. As in the previous results, a noisy behavior is observed in Figure 12. Moreover, a small value is obtained if no additional optimizations are included.

Fig. 4
figure 4

Quaternion vectorial components for case 1 with classical MPC

Fig. 5
figure 5

Angular velocity components for case 1 with classical MPC

Fig. 6
figure 6

Quaternion vectorial components for case 1 with MPC with optimization of virtual reference signal and integrator state

Fig. 7
figure 7

Angular velocity components for case 1 with MPC with optimization of virtual reference signal and integrator state

Fig. 8
figure 8

Control input of case 1 with classical MPC

Fig. 9
figure 9

Control input of case 1 with MPC with optimization of virtual reference signal and integrator state

Fig. 10
figure 10

Gimbal angles of case 1 with classical MPC

Fig. 11
figure 11

Gimbal angles of case 1 with MPC with optimization of virtual reference signal and integrator state

Fig. 12
figure 12

Singularity index of case 1 with classical MPC

Fig. 13
figure 13

Singularity index of case 1 with MPC with optimization of virtual reference signal and integrator state

In the second simulation, as before, a step variation of the three angular velocities is considered with two variations of the angular velocities. A simulation time of 10 seconds is considered: (i) \(\omega _d = [2,2,2]^T\) deg/s between 2 and 4 seconds, (ii) \(\omega _d = [4,4,4]^T\) deg/s between 5.5 and 8 seconds. As for the previous case, the state variables (angular velocities and quaternion) are analyzed for the classical MPC and the one with optimization of virtual reference signal and integrator state. Moreover, control input and gimbal angles are also considered. All the results are in Figs. 14,15, 16, 17, 18, 19, 2021. Finally, the singularity index is analyzed to show the effectiveness of the proposed MPC controller. As in Figs. 22 and 23, even in this simulation the singularity index of the MPC with optimization of virtual reference signal and integrator state is greater than the classical MPC with no additional optimizations.

Fig. 14
figure 14

Quaternion vectorial components for case 2 with MPC with optimization of virtual reference signal and integrator state

Fig. 15
figure 15

Angular velocity components for case 2 with MPC with optimization of virtual reference signal and integrator state

Fig. 16
figure 16

Control input of case 2 with MPC with optimization of virtual reference signal and integrator state

Fig. 17
figure 17

Gimbal angles of case 2 with MPC with optimization of virtual reference signal and integrator state

Fig. 18
figure 18

Quaternion vectorial components for case 2 with MPC with optimization of virtual reference signal and integrator state

Fig. 19
figure 19

Angular velocity components for case 2 with classical MPC

Fig. 20
figure 20

Control input of case 2 with classical MPC

Fig. 21
figure 21

Gimbal angles of case 2 with classical MPC

Fig. 22
figure 22

Singularity index of case 2 with classical MPC

Fig. 23
figure 23

Singularity index of case 2 with MPC with optimization of virtual reference signal and integrator state

These simulations demonstrate the effectiveness of the MPC controller with additional features, that optimize the virtual reference signal and the integrator state.

5.2 Second set of simulations

In this set of simulations, triangular variation of one angular velocity is proposed. This set of simulations is performed in simulation and by experimental tests as well (as detailed in Sect. 5). As in the previous section we show that the MPC with integrator state and virtual reference has better performance than the classical one. Thus, in the following simulations we further investigate the performance of the MPC with integrator state and virtual reference.

As before, two cases are analyzed: (1) a rotation around the X-axis, namely the direction of \([1,0,0]^T\) of \(\omega _d = [5,0,0]^T\) deg/s, and (2) a rotation around Z axis of \(\omega _d = [0,0,5]^T\) deg/s. In both cases a triangular shape of the desired value is considered. Moreover, the desired quaternion is evaluated from Eq. (19).

As from Figs. 24 and 25, the controller is able to track the desired behavior, with a small control authority (Fig. 26). Moreover, the singularity index (Fig. 27) shows the ability of the controller to avoid singularity.

Fig. 24
figure 24

Angular velocity components for a rotation around X axis

Fig. 25
figure 25

Quaternion vectorial components for a rotation around X axis

Fig. 26
figure 26

Control Input for a rotation around X axis

Fig. 27
figure 27

Singularity index for a rotation around X axis

Similar results are obtained for the rotation around Z-axis (Figs. 28, 29, 30 and 31). The singularity index shown in Fig. 31 implies that if the value of the index is close to zero, the CMG system is close to a singular state. Thus, the higher is this index, the higher is the controller ability to avoid singularity.

Fig. 28
figure 28

Angular velocity components for a rotation around Z axis

Fig. 29
figure 29

Quaternion vectorial components for a rotation around Z axis

Fig. 30
figure 30

Control Input for a rotation around Z axis

Fig. 31
figure 31

Singularity index for a rotation around Z axis

6 Experimental results

After performing simulations in Matlab environment, the MPC with optimization of the virtual reference signal is converted in C++ program language, and applied to the testbed in Fig. 3.

Corresponding to the simulations in Sect. 4.2, we perform two cases of experiments: (1) a rotation around X axis of \(\omega _d = [5, 0, 0]^T\) deg/s, and (2) a rotation around Z axis of \(\omega _d = [0, 0, 5]^T\) deg/s. The desired trajectories of the angular velocity and the quaternion are the same as in Sect. 4.2, which are shown in the dotted lines in Figs. 32 and 36, and Figs. 33 and 37, respectively.

The experimental results of the X-axis rotation are shown in Figs. 32, 33, 34 and 35. Figs. 32 and 33 exhibit the angular velocity and the vectorial part of the quaternion of the testebed, respectively. Figure 34 shows the control inputs of the system. In addition, the singularity index is indicated in Fig. 35. Those experimental results correspond to the simulation results in Figs. 24, 6, 7 and 27 in Sect. 4.2.

Next, the experimental results of the Z-axis rotation are shown in Figs. 36, 37, 38 and 39. Similarly, the angular velocity, the vectorial part of the quaternion, the control inputs, and the singularity index are respectively shown in Figs. 3637, 38 and 39. Those experimental results correspond to the simulation results in Figs. 28, 29, 30 and 31 in Sect. 4.2.

The unmodeled gravity torque due to the misalignment between the center of rotation and the center of gravity of the testbed inevitably arises in the ground experiments unlike the simulations. In particular, the X-axis rotation is seriously affected by the gravity torque disturbance. Moreover, under this setting, since the singular direction of two of the four CMGs is aligned to that of the required torque, the X-axis rotation is much difficult than the Z-axis rotation. Nonetheless, the present MPC controller compensates the disturbance and successfully achieves attitude tracking control in both cases. These experiments verify the effectiveness and feasibility of the proposed method.

Fig. 32
figure 32

Angular velocity components of the testbed in the experiment of X-axis rotation

Fig. 33
figure 33

Vectorial part of the quaternion in the experiment of X-axis rotation

Fig. 34
figure 34

Control input signals in the experiment of X-axis rotation

Fig. 35
figure 35

Singularity index in the experiment of X-axis rotation

Fig. 36
figure 36

Angular velocity components of the testbed in the experiment of Z-axis rotation

Fig. 37
figure 37

Vectorial part of the quaternion in the experiment of Z-axis rotation

Fig. 38
figure 38

Control input signals in the experiment of Z-axis rotation

Fig. 39
figure 39

Singularity index in the experiment of Z-axis rotation

7 Conclusions

Control Moment Gyros (CMGs) are widely used for precise attitude control. This paper describes the attitude control problem of a spacecraft, using a Model Predictive Control (MPC) systems. The features of the considered linear MPC are: (i) a virtual reference, to guarantee input constraints satisfaction, and (ii) an integrator state as a servo compensator, to reduce the steady-state error. Moreover, the real-time implementability is discussed, considering an optimized solver for embedded systems. Good performance are observed in simulations. However, the proposed linear MPC control system is not able to handle with additive disturbances acting on the experimental testbed and it is only partially able to compensate this disturbance. In future works a control system able to handle and compensate the gravity gradient torque will be considered. Moreover, the gravity gradient disturbance will be also included in the model of the testbed itself.