1 Introduction

The main motivation behind this work is the development of an Attitude Determination and Control System (ADCS) for a future sounding rocket from a student rocketry team from Instituto Superior Técnico (IST), named Rocket Experiment Division (RED). The ADCS design assumes that the rocket uses Thrust Vector Control (TVC) technology as the actuation method, and aims to control the rocket’s pitch and yaw angles. The roll angle is assumed to be controlled by an additional roll control system whose design is out of the scope of this work.

During the atmospheric flight phase of a rocket, stabilisation can be achieved through the use of aerodynamic fins. With a correct design of the fins, the vehicle can be made naturally stable [1]. However, the rocket is subjected to various external disturbances, such as wind gusts, which prevent the vehicle to follow a desirable, pre-calculated trajectory or, even more intense, completely destabilise it [2]. It is then clear the necessity of having an active attitude control and stabilisation system that not only ensures the stability of the rocket, but allows to actively correct its trajectory in order to achieve specific mission goals. As for the actuation method, Thrust Vector Control (TVC), or thrust vectoring for short, is used by most launch vehicles and works by redirecting the thrust vector in order to create a control torque [3]. With respect to other actuation techniques, like actively controlled fins, TVC allows for a wider range of operating conditions and provides better efficiency [4].

The control system design tends to be very conservative in the aerospace industry. Restricting the dynamic analysis to accommodate more sophisticated control design techniques risks the later realisation that such restrictions would have to be lifted and would invalidate the control design. Among the classical techniques, the Proportional-Integral-Derivative (PID) control is on the core of most commonly used launch vehicle control systems [3, 5]. Although widely used, PID control has its downsides when it comes to robustness and external disturbances rejection [6]. The problem of controlling ascending launch vehicles is dominated by parameter uncertainty, which in face of the lack of robustness of the PID controller may be a concerning issue. Moreover, the rocket flight parameters considerably change throughout the flight. To overcome this, gain scheduling techniques have been proposed, that rely on the linearization of the dynamics at different operating conditions. Still in the linear domain, the use of optimal controllers, such as the Linear Quadratic Regulator (LQR), provides more robustness and ensures a locally optimal solution for a given cost function [6, 7]. As a way to improve the robustness of linear time-varying controllers, real-time parameter estimators can be introduced in the control loop to form an adaptive control system. The online identification of system parameters allows the controller to act on a more accurate representation of the system dynamics [8].

Non-linear control and estimation techniques have also been proposed [9, 10], and come with the advantage of ensuring a global solution, not dependent on the specific mission nor vehicle. However, this type of control and estimation laws often have to simplify complete non-linear dynamics in order to obtain a global solution. If relevant dynamics are discarded, the system might fail in a real implementation scenario. Besides that, these methods all have particular design characteristics which make it harder to develop a standardised verification and validation procedure to meet the imposed system requirements [3, 5].

Although several solutions to the rocket attitude control problem can be found in the literature [7, 11, 12], many fail to capture all the relevant dynamics and/or oversimplify the problem, while most assume full-state knowledge, creating a considerable gap between theoretical design and implementation. Hence, the main contribution of this paper is a robust ADCS, which integrates both the navigation and control systems, relying on computationally efficient algorithms and that can be implemented in sounding rockets through readily available low-cost components. Furthermore, the design process considers the 6 DoF, as opposed to restricting the analysis to the pitch plane, as well as the time-varying nature of the system, focussing on the entire trajectory rather than a single operating point, contrarily to what is found in the literature when using linear optimal control and estimation techniques. In this way, the implementation of the system in a real case scenario is facilitated.

To achieve this goal, several intermediate contributions were necessary, always having in mind the reliability and robustness of the proposed solutions: an original generic state-space representation for linear and optimal control design in the 6 DoF; a gain-scheduled optimal pitch and yaw controller resorting to the LQR technique with added integrative action; and a navigation system, based on measurements available on-board, to provide accurate estimates on the rocket’s state, including a novel linear time-varying parameter estimator to estimate in real-time aerodynamic forces and moments acting on the vehicle.

2 Rocket Dynamics and Kinematics Modelling

To design the ADCS, a mathematical model that represents the translational and rotational dynamics and kinematics of the rocket in the 6 DoF is necessary.

2.1 Assumptions

Some assumptions are used to derive the model. The rocket is considered to be a rigid body, meaning no elastic behaviours are modelled. This assumption is considered valid for control system design given the smaller size of typical sounding rockets, and consequent reduced impact of elastic behaviour on the overall dynamics. The rocket is assumed to be axially symmetric, as well as the mass allocation, which means that the principal inertia axes coincide with the body axes, the centre of mass is on the longitudinal axis, and the aerodynamic behaviour is identical in both the pitch and yaw planes. This assumption is standard given that launch vehicles, and more specifically sounding rockets, are designed in order to respect this symmetry. Finally, neither the curvature nor rotation of the Earth are taken into account, which is also a reasonable assumption considering the typical altitude and ground distance covered by the class of vehicles under study.

2.2 Reference Frames

To describe the dynamics and kinematics of the rocket, it is crucial to define the reference frames to be used. Two reference frames are used: a body-fixed one (Fig. 1a), where the equations of motion are written; and an inertial space-fixed one (Fig. 1b). The body-fixed reference frame has its origin located in the centre of mass of the vehicle.

Fig. 1
figure 1

Body-fixed a and inertial b reference frames

The x-axis (\(X_b\)) is along the rocket’s longitudinal axis, while the z-axis (\(Z_b\)) and y-axis (\(Y_b\)) complete the orthogonal reference frame. As for the inertial space-fixed reference frame, given that neither the curvature nor the rotational motion of the Earth are taken into account, a simple orthogonal frame centred in the launch location is used. The x-axis (\(X_e\)) is pointing upwards, so that for a zero inclination launch the x-axes of both reference frames are aligned; and the other two axes (\(Y_e\) and \(Z_e\)) are preferably aligned with a pair of cardinal directions.

With the reference frames detailed, it is necessary to define the coordinate transformation between them. This is done using a sequential rotation of the body frame relative to the Earth frame defined by the three Euler angles (\(\varvec{\lambda }= \begin{bmatrix} \phi&\theta&\psi \end{bmatrix}^T\)): \(\textbf{R}(\phi ,\theta ,\psi )=\textbf{R}_z(\psi )\,\cdot \,\textbf{R}_y(\theta )\,\cdot \,\textbf{R}_x(\phi )\), where \(\phi\) is the Euler angle of rotation of the body around the x-axis of the Earth frame, also known as roll; \(\theta\) is the Euler angle of rotation of the body around the y-axis of the Earth frame, also known as pitch; and \(\psi\) is the Euler angle of rotation of the body around the z-axis of the Earth frame, also known as yaw.

The Euler angles describe the attitude of the rocket, representing the variables to be controlled by the attitude control system. The coordinate transformation from the body frame to the Earth frame is then defined by the following transformation matrix [13]:

$$\begin{aligned} \textbf{R} = \begin{bmatrix} c_{\theta }c_{\psi } &{} s_{\phi }s_{\theta }c_{\psi } - c_{\phi }s_{\psi } &{} c_{\phi }s_{\theta }c_{\psi } + s_{\phi }s_{\psi }\\ c_{\theta }s_{\psi } &{} s_{\phi }s_{\theta }s_{\psi } + c_{\phi }c_{\psi } &{} c_{\phi }s_{\theta }s_{\psi } - s_{\phi }c_{\psi }\\ -s_{\theta } &{} s_{\phi }c_{\theta } &{} c_{\phi }c_{\theta } \end{bmatrix}\,, \end{aligned}$$

where c and s stand as abbreviations for the trigonometric functions. The inverse transform, from the Earth frame to the body frame, is defined by the transpose (\(\textbf{R}^T\)).

2.3 External Forces and Moments

From the dynamic point of view, sounding rockets experience four main forces during a flight: Weight, Thrust, and the aerodynamic forces—lift and drag.

2.3.1 Gravity Model

Considering the Earth as a perfect sphere, the gravitational acceleration, g, is assumed to vary only with altitude. This variation is given by \(g=g_0\cdot R_E^2/(R_E+h)^2\), where \(g_0\) is the gravitational acceleration constant at surface level, \(R_E\) is the mean Earth radius, and h is the altitude. The gravitational force, expressed in the Earth frame, is given by \({^{E}{\textbf{F}_\textbf{g}}} =\left[ -mg\,\, 0\,\,0\right] ^T\), where m is the rocket’s mass. To obtain it in the body frame, the rotation matrix \(\textbf{R}^\textbf{T}\) is used, yielding \({^{B}{\textbf{F}_\textbf{g}}} = \left[ -mg\cdot c_{\theta }c_{\psi }\,\, -mg\cdot (s_{\phi }s_{\theta }c_{\psi } - c_{\phi }s_{\psi })\,\, -mg\cdot (c_{\phi }s_{\theta }c_{\psi } + s_{\phi }s_{\psi }) \right] ^T\).

2.3.2 Propulsion Model

The propulsion model was derived using equations mainly obtained from [4], considering ideal propulsion and all its underlying assumptions. The thrust produced by the rocket motor is simply

$$\begin{aligned} T = \underbrace{|\dot{m}|\cdot v_e}_{\text {Dynamic}} + \underbrace{(p_e - p_a)\cdot A_e}_{\text {Static}}\,, \end{aligned}$$

where \(\dot{m}\) is the mass flow rate, \(v_e\) is the effective exhaust velocity, \(p_e\) is the nozzle exit pressure, \(p_a\) is the atmospheric pressure, and \(A_e\) is the nozzle exit area. Two separate contributions can be identified: the dynamic one, caused by the exhaust of the expanded combustion gases; and the static, caused by the pressure gradient between the nozzle exit and the atmosphere.

Considering that the most common propulsion technology for sounding rockets is solid propulsion, and that it is the technology used by RED, a model that uses the internal combustion equations, available in [4, 14], as well as the solid propellant characteristics, is implemented to calculate the thrust produced by the motor, T, the associated mass flow rate, \(\dot{m}\), and the nozzle exit pressure, \(p_e\). The propellant considered for this work was the mixture of potassium nitrate with sorbitol (KNSB), a propellant commonly used in student rocketry known as “rocket candy", with its properties present in [15]. The mass and geometry of the propellant grains can be altered to obtain different thrust profiles.

2.3.3 TVC Actuation

By controlling the direction of the thrust force (or vector), TVC actuation produces torques that act on the rocket’s centre of mass, influencing its rotation in pitch and yaw. The decomposition of the propulsive force in the three body axes can be done as illustrated in Fig. 2.

Fig. 2
figure 2

Thrust vector decomposition in the body axes

According to it, the thrust vector is decomposed using the angles \(\mu _p\) and \(\mu _y\), where \(\mu _p\) is the gimbal angle that, on its own, produces a pitching moment, and \(\mu _y\) is the one that produces a yawing moment. Using these angles, the propulsive force in the body frame is given by \({^{B}{\textbf{F}_\textbf{p}}} = \left[ T\cos {\mu _p}\cos {\mu _y}\,\, -T\cos {\mu _p}\sin {\mu _y} \,\, -T\sin {\mu _p} \right] ^T\), and the correspondent control moment is \({^{B}{\textbf{M}_\mathbf {{p}}}} = \left[ 0\,\, -T\sin {\mu _p}\, l\,\,\, T\cos {\mu _p}\sin {\mu _y}\, l \right] ^T\) [6], where l is the moment arm, which corresponds to the distance between the nozzle gimbal point and the centre of mass of the rocket.

2.3.4 Aerodynamic Forces and Moments

The rocket will be subjected to aerodynamic forces and moments resulting from its interaction with the fluid medium composing the atmosphere. Starting by the forces, they are expressed in the body axes according to \({^{B}{\textbf{F}_\textbf{a}}} = \left[ -\overline{q}\, C_A\, S\,\,\, \overline{q}\, C_{Y}\, S\,\, -\overline{q}\, C_{N}\, S \right] ^T\), where \(C_A\) is the axial aerodynamic force coefficient, \(C_{Y}\) is the lateral aerodynamic force coefficient, \(C_{N}\) is the normal aerodynamic force coefficient, \(\overline{q}\) is the dynamic pressure and S is a reference area, usually corresponding to the cross sectional area of the fuselage.

The axial and normal aerodynamic forces correspond to the body axes components of lift and drag, and are related through the aerodynamic angles—the angle of attack, \(\alpha = \arctan \left( w_\textrm{rel}/u_\textrm{rel}\right)\), and the sideslip angle, \(\beta = \arcsin \left( v_\textrm{rel}/V_\textrm{rel}\right)\), where \(u_\textrm{rel}\), \(v_\textrm{rel}\), and \(w_\textrm{rel}\) are the components of the relative velocity vector with respect to the atmosphere, and \(V_\textrm{rel}\) its magnitude. The force coefficients can be determined using a linear relation with the aerodynamic angles, \({C_Y} = {C_Y}_\beta \, \beta\) and \({C_N} = {C_N}_\alpha \, \alpha\), whose derivatives (\({C_Y}_\beta\) and \({C_N}_\alpha\)) depend mainly on the angle itself and Mach number.

As for the aerodynamic moments, in the body axes they are given by \({^{B}{\textbf{M}_\textbf{a}}} =\left[ \, \overline{q}\, C_l\, S\, d\,\,\, \overline{q}\, C_m\, S\, d\,\,\, \overline{q}\, C_n\, S\, d \,\right] ^T\), where \(C_l\), \(C_m\), and \(C_n\) are, respectively, the rolling, pitching, and yawing moment coefficients, and d is a reference length, usually corresponding to the diameter of the fuselage. If the reference moment station is defined as the centre of pressure, and its location, \(x_{cp}\), can be determined, the reference moments are zero and the moment coefficients take the form \(C_l={C_l}_p\, p\,d/(2V_\textrm{rel})\), \(C_m=-{C_N}\,SM+ (C_{m_{q}}+C_{m_{\dot{\alpha }}})\, q\,d/(2V_\textrm{rel})\), and \(C_n=-{C_Y}\,SM + (C_{n_{r}}+C_{n_{\dot{\beta }}})\, r\,d/(2V_\textrm{rel})\), where the static stability margin, \(SM = (x_{cp}-x_\textrm{cm}) /d\), intuitively appears, p, q, and r, are the body angular velocities, and \(C_{l_p}\), \(C_{m_q}\), \(C_{m_{\dot{\alpha }}}\), \(C_{n_r}\), and \(C_{n_{\dot{\beta }}}\) are all aerodynamic damping coefficients.

2.4 6 DoF Equations of Motion

2.4.1 Translational Motion

By applying Newton’s second law, and taking into account that the body frame is a rotating one, we obtain the translation dynamics,

$$\begin{aligned} \dot{\textbf{v}} = \frac{1}{m}\, \left( {^{B}{\textbf{F}_\textbf{g}}}+ {^{B}{\textbf{F}_\textbf{p}}}+{^{B}{\textbf{F}_\textbf{a}}}\right) - \textbf{S}(\varvec{\omega })\,\textbf{v}\,, \end{aligned}$$
(1)

where \(\textbf{v} = \left[ u\,\, v\,\, w \right] ^T\) is the velocity vector in the body frame, \(\varvec{\omega }= \left[ p\,\,q \,\,r \right] ^T\) is the angular velocity vector in the body frame, \(\textbf{S}(.)\) is a skew-symmetric matrix, and the mass derivative term has been included in the propulsive force. By substituting the external forces in (1), the dynamics can be particularised in the body acceleration components:

$$\begin{aligned} {\left\{ \begin{array}{ll} \dot{u} &{}= -g\,c_{\theta }\,c_{\psi } -\frac{\overline{q}}{m}\,S\,C_A + \frac{T}{m}c_{\mu _p}\,c_{\mu _y} -q\,w + r\,v \\ \dot{v} &{}= -g\,(s_{\phi }\,s_{\theta }\,c_{\psi }-c_{\phi }\,s_{\psi }) + \frac{\overline{q}}{m}\,S\,C_{Y} - \frac{T}{m}\,c_{\mu _p}\,s_{\mu _y}- r\,u +p\,w \\ \dot{w} &{}= -g\,(c_{\phi }\,s_{\theta }\,c_{\psi }+s_{\phi }\,s_{\psi }) - \frac{\overline{q}}{m}\,S\,C_{N} - \frac{T}{m}\,s_{\mu _p}-p\,v + q\,u\\ \end{array}\right. }. \end{aligned}$$
(2)

2.4.2 Rotational Motion

Euler’s equation for rigid body rotational motion yields

$$\begin{aligned} {^{B}{\textbf{M}_\textbf{a}}} + {^{B}{\textbf{M}_\textbf{p}}} = \textbf{J}\,\dot{\varvec{\omega }} + \varvec{\omega }\times \textbf{J}\,\varvec{\omega }\,, \end{aligned}$$
(3)

where \(\textbf{J}\) is the inertia matrix. Following the axial symmetry assumption, the cross-products of inertia can be assumed as zero and the y and z terms can be assumed equal, resulting in a diagonal matrix, \(\textbf{J} = diag\,(J_l,J_t,J_t)\,\), where \(J_l\) denotes the longitudinal inertia and \(J_t\) denotes the transverse inertia. By substituting the inertia matrix \(\textbf{J}\) and the external moments in the body frame in (3), the explicit dynamics are obtained in terms of the body angular acceleration components:

$$\begin{aligned} {\left\{ \begin{array}{ll} \dot{p} = {J_l}^{-1}\,(\overline{q}\,S\,d\,C_l + \tau _r + \mu _r)\\[0.1cm] \dot{q} = {J_t}^{-1}\,(\overline{q}\,S\,d\,C_m - T\,s_{\mu _p}\,l)\\[0.1cm] \dot{r} = {J_t}^{-1}\,(\overline{q}\,S\,d\,C_n + T\,c_{\mu _p}\,s_{\mu _y}\,l)\\ \end{array}\right. }, \end{aligned}$$
(4)

where \(\mu _r\) represents the rolling moment caused by the additional roll control system and \(\tau _r\) accounts for external disturbances. Given that the aim of this work is to control the pitch and yaw angles only, the additional roll control system is assumed to be able to reject disturbances on this axis (\(\tau _r\)) and control the roll angle. Its inclusion in the model is only for the sake of completeness and is not considered during the design. Finally, the rotational kinematics are given by the time derivative of the Euler angles [13]:

$$\begin{aligned} {\left\{ \begin{array}{ll} \dot{\phi } =p+(q\,s_{\phi }+r\,c_{\phi })\,t_{\theta }\\ \dot{\theta } =q\,c_{\phi } - r\,s_{\phi }\\ \dot{\psi } = \displaystyle \frac{q\,s_{\phi } + r\,c_{\phi }}{c_{\theta }}\\ \end{array}\right. }. \end{aligned}$$
(5)

It is noted that using the Euler angles a singularity arises for \(\theta = \pm \frac{\pi }{2}\), however, the way the reference frames are defined prevents the rocket to reach this attitude inside the admissible range of operation (far from horizontal orientation). By grouping (2), (4), and (5) the 6 DoF non-linear model of the rocket is fully defined.

2.5 Reference Rocket

A specific rocket is needed to serve as reference for the ADCS design. In this way, a preliminary design for a future RED’s rocket with Thrust Vector Control is performed. The rocket is designed to have a burning phase coinciding with the full duration of the climb, so that TVC can be used to control its attitude up to apogee. It is also required that the terminal velocity is inside a safe range to allow the correct activation of the recovery system. To meet these design goals, the solid motor parameters are iteratively tested using the propulsion model, and the flight for a vertical undisturbed trajectory is simulated. Tables 1 and 2 respectively present the main rocket characteristics and the simulation results.

Table 1 Main rocket characteristics
Table 2 Vertical trajectory parameters

3 Attitude Control System Design

3.1 Model Linearization

To design an optimal, linear controller, it is necessary to obtain a linear version of the model and respective state-space representation. The non-linear model can be linearized at equilibrium points of the system using a Taylor series expansion, considering small perturbations. For the case of a rocket, conditions change considerably throughout the flight, hence, it is not correct to choose a single equilibrium point to linearize the system. Instead, a reference trajectory is selected and the system is linearized at multiple operating points. The outcome is a linear time-varying system.

When obtaining the linear version of the system, it is advantageous to consider some assumptions: the roll rate, p, is considered to be zero as it will be controlled by an external roll control system, reducing the order of the system by one; the wind is assumed to be zero, allowing to directly use the linear velocity in the body frame in the aerodynamic terms; the actuator dynamics are not included in the model; and the system parameters are considered to be constant at the linearization points, removing the dependencies on the state variables when computing the Taylor derivatives. By applying a Taylor series expansion to the non-linear system around the operating points, and considering these assumptions, a linear time-varying system in the perturbation domain is obtained, that can be represented in the state-space form:

$$\begin{aligned}{} & {} \delta \textbf{x} = \left[ \,\delta u\,\, \delta v\,\, \delta w\,\, \delta q\,\, \delta r\,\, \delta \phi \,\, \delta \theta \,\, \delta \psi \,\right] ^{T},\nonumber \\{} & {} \delta \textbf{u} = \left[ \,\delta \mu _p\,\, \delta \mu _y\,\right] ^{T}, \end{aligned}$$
(6a)
$$\begin{aligned}{} & {} \delta \dot{\textbf{x}}(t) = \textbf{A}(t)\cdot \delta \textbf{x}(t) + \textbf{B}(t)\cdot \delta \textbf{u}(t), \end{aligned}$$
(6b)

where \(\textbf{A}(t)\) and \(\textbf{B}(t)\) are the state-space matrices given by the first-order Taylor derivatives with respect to system states and inputs, respectively, calculated at the operating points.

Regarding the attitude reference that defines the reference trajectory, a varying pitch trajectory, in which the controller restricts the motion to the pitch plane (yaw equal to zero) and makes the rocket deviate from the vertical to later recover it, is selected. In this way, it is ensured that the apogee is reached further away from the launch site, increasing safety. Figure 3 shows the reference pitch angle and rate over time.

Fig. 3
figure 3

Reference pitch rate a and angle b over time

Since the system is naturally unstable, it is necessary to find the time evolution of the nominal control inputs that allows the rocket to nominally follow the trajectory, defined by an attitude reference over time. This is done using a PID controller that in simulation, without perturbations, is able to stabilise the vehicle and track the attitude reference. The input values over time are then stored to use as predetermined feedforward control inputs.

It is possible to identify two distinct sections of the reference trajectory: a first section up to \(t = 25\,\)s in which motion is strictly vertical, and a second section up to burnout in which pitch is varying. For the varying pitch section, we have that: \(\phi _0 = \psi _0 = 0\), \(v_0 =0\), \(r_0 = 0\), and \(\mu _{y_0} = 0\). This results in a simplified version of the state-space representation, for which the longitudinal and lateral modes are decoupled:

$$\begin{aligned}{} & {} \delta \textbf{x}_\textrm{lon} = \left[ \delta u\,\,\delta w\,\,\delta q\,\,\delta \theta \right] ^{T},\\{} & {} \delta \textbf{u}_\textrm{lon}= [\delta \mu _p]\\{} & {} \delta \textbf{x}_\textrm{lat} = \left[ \delta v\,\,\delta r\,\,\delta \phi \,\, \delta \psi \right] ^{T},\\{} & {} \delta \textbf{u}_\textrm{lat} = [\delta \mu _y] \end{aligned}$$

In the vertical section, we have that: \(\phi _0 = \theta _0=\psi _0 = 0\), \(v_0 = w_0 =0\), \(q_0 = r_0 = 0\), and \(\mu _{p_0} = \mu _{y_0}=0\). This results in a simplified version of the decoupled state-space representation, for which \(\delta u\) and \(\delta \phi\) are no longer states of the system.

Finally, it is important to determine the location of the system poles throughout the nominal trajectory to derive the open-loop stability. For a time-varying system, the stability is not mathematically guaranteed with this method, however, the study is carried out to understand the behaviour of the system throughout the flight. Figure 4 details the pole evolution (from blue to green) during the vertical section and the poles at \(t = 50\,\)s, which serves as example for the distribution type during the varying pitch section.

Fig. 4
figure 4

Poles for the vertical section (up to \(t = 25\,\)s) a and poles at \(t = 50\,\)s b

Looking at the different pole distributions during the flight, some conclusions can be made. First, the system has poles located in the right-hand side of the complex plane for the entire trajectory, meaning that it is naturally unstable. This was expected due to the negative static stability margin caused by the absence of aerodynamic fins. Second, during the vertical section, there is an equivalence between the lateral and longitudinal modes, verified by the identical pole distributions, which is due to the symmetry of the vehicle and to the equality in the nominal values of the corresponding states. Thirdly, the system has complex conjugate poles with positive real part during the first seconds of the flight, which indicates natural unstable oscillatory behaviour, after which all poles start to be located on the real axis. Finally, it is concluded that the velocity of the rocket is a driving factor for the response of the system—as velocity increases during the flight, the system is seen to have higher magnitude poles and hence faster response. This is attributed to the fact that at higher velocities the magnitude of the aerodynamic forces and moments is also higher, causing higher accelerations on the system when the inputs are actuated.

3.2 Linear Quadratic Integral (LQI) Control

Using the linear time-varying state-space representation of the system, a linear quadratic regulator (LQR) is designed with the addition of an integral action, also known as linear quadratic integral control (LQI). The LQR is a technique that finds the optimal gain matrix \(\textbf{k}\) for the linear control law \(\textbf{u} = -\textbf{k}\,\textbf{x}\), which minimises a quadratic cost function given by

$$\begin{aligned} J = \int _{t}^{T} [\,\textbf{x}'(\tau )\,\varvec{\mathcal {Q}}\,\textbf{x}(\tau ) + \textbf{u}'(\tau )\,\varvec{\mathcal {R}}\,\textbf{u}(\tau )\,] \,d\tau \,, \end{aligned}$$

where \(\varvec{\mathcal {Q}}\) is a positive semi-definite matrix and \(\varvec{\mathcal {R}}\) is a positive definite matrix [16]. In the cost function, the quadratic form \(\mathbf {x'\varvec{\mathcal {Q}}x}\) represents a penalty on the deviation of the state x from the origin, and the term \(\mathbf {u'\varvec{\mathcal {R}}u}\) represents the cost of control, making \(\varvec{\mathcal {Q}}\) and \(\varvec{\mathcal {R}}\) the tuning parameters for the resultant controller. Using the infinite-horizon version, which means taking T as infinity, the solution which minimises the cost function and guarantees closed-loop asymptotic stability is the constant gain matrix \(\textbf{k} = \varvec{\mathcal {R}}^{-1}\,\textbf{B}^T\,\textbf{P}\), where \(\textbf{P}\) is the solution to the Algebraic Riccati Equation (ARE) \(\textbf{P}\,\textbf{A} + \textbf{A}^{T}\,\textbf{P}-\textbf{P}\,\textbf{B}\,\varvec{\mathcal {R}}^{-1}\,\textbf{B}^T\,\textbf{P} + \varvec{\mathcal {Q}}=0\).

Since the system is time-varying, the ARE has to be solved for models coming from each linearization point, resulting in a set of gain matrices to be selected, or scheduled, throughout the flight.

The LQR feedback control law ideally drives the states of the system in the perturbation domain to zero, ensuring that the nominal values throughout the trajectory are followed. However, it does not guarantee a zero tracking error for non-zero references in terms of attitude. In order to have a zero reference tracking error, and to increase the robustness of the controller, an integral action that acts on the attitude tracking error is added, according to the scheme in Fig. 5.

Fig. 5
figure 5

LQI control scheme

Let the difference between the reference signal, \(\textbf{r}\), and the output of the system, \(\textbf{y}\), (the tracking error) be the time derivative of the state-space variables that result from adding the referred integrator, \(\mathbf {x_i}\). The state-space representation of the resulting regulator can be obtained by combining the open-loop state-space representation with the feedback law,

$$\begin{aligned} \dot{\textbf{z}} = \left( \begin{bmatrix} \textbf{A} &{} \textbf{0}\\ -\textbf{C} &{} \textbf{0} \end{bmatrix}-\begin{bmatrix} \textbf{B}\\ \textbf{0} \end{bmatrix}\,\textbf{K}\right) \textbf{z} + \begin{bmatrix} \textbf{0} \\ 1 \end{bmatrix}\,\textbf{r}\,, \end{aligned}$$

where \(\textbf{z} =\left[ \,\textbf{x}\,\,\mathbf {x_i}\,\right] ^T\) is the augmented state vector and \(\textbf{C}\) is the output matrix that selects the output of the system from the original state vector (\(\textbf{y} = \textbf{C}\,\textbf{x}\)). The optimal gain \(\textbf{K}\) is obtained by solving the ARE using the rearranged system matrices,

$$\begin{aligned} \mathbf {\overline{A}} = \begin{bmatrix} \textbf{A} &{} \textbf{0}\\ -\textbf{C} &{} \textbf{0} \end{bmatrix}\,,\hspace{10pt} \mathbf {\overline{B}} = \begin{bmatrix} \textbf{B}\\ \textbf{0} \end{bmatrix}\,. \end{aligned}$$

Considering the decoupling between the longitudinal and lateral modes, the decoupled augmented state vectors are \(\delta \textbf{z}_{lon} = [\delta u\,\, \delta w\,\, \delta q\,\,\delta \theta \,\, \delta \theta _i]^{T}\) and \(\delta \textbf{z}_{lat} = [\delta v\,\, \delta r\,\, \delta \psi \,\, \delta \psi _i]^{T}\), where \(\delta \theta _i\) and \(\delta \psi _i\) are the integral states. This implies that the \(\textbf{A}\), \(\textbf{B}\) are divided into the longitudinal and lateral modes, and that the \(\textbf{C}\) matrix for the lateral mode is the one that selects the yaw angle, while for the longitudinal mode is the one that selects the pitch angle.

The design degree of freedom is the selection of the tuning matrices \(\varvec{\mathcal {Q}}\) and \(\varvec{\mathcal {R}}\), which will also be divided into the longitudinal and lateral mode. First of all, setting all non-diagonal entries to zero, and only focussing on the diagonal ones, allows for a more intuitive matrix selection given by the “penalty” method. According to this method, the diagonal entries of the \(\varvec{\mathcal {Q}}\) matrix will determine the relative importance of the state variables in terms of origin tracking performance, while the diagonal entries of the \(\varvec{\mathcal {R}}\) matrix allow to directly adjust the control effort for each input. Therefore, the weighting matrices have the following generic format, separated for each mode,

$$\begin{aligned} \varvec{\mathcal {Q}}_\textrm{lon}=\, & {} diag\,(q_u,\,q_w,\,q_q,\,q_{\theta },\,q_{\theta _i}),\\ \varvec{\mathcal {Q}}_\textrm{lat}=\, & {} diag\,(q_v,\,q_r,\,q_\psi ,\,q_{\psi _i}),\\ \mathcal {R}_\textrm{lon}=\, & {} r_{\mu _p},\hspace{10pt} \mathcal {R}_{lat} = r_{\mu _y}. \end{aligned}$$

Given the nature of the TVC actuation, trying to control the linear velocities would conflict with the attitude control, specially for non-zero attitude references. Hence, the linear velocity related terms are set as zero. By doing this, the associated gains will have negligible magnitude, allowing to use partial state feedback with \({\textbf{k}_\textbf{lon}} = \left[ k_q \,\,\,k_\theta \,\,\,k_{\theta _i}\right]\) and \({\textbf{k}_\textbf{lat}} = \left[ k_r\,\,\,k_\psi \,\,\,k_{\psi _i}\right]\).

The tuning parameters are iteratively adjusted looking at the closed-loop poles and at the step response performance in the linear domain, including the actuator dynamics, modelled as a first-order system. Regarding the closed-loop poles, the control law allowed to stabilise all operating points, placing all closed-loop poles in the left-hand side of the complex plane. Table 3 details the step response parameters for multiple operating points.

Table 3 Closed-loop step response parameters

4 Navigation System Design

So far, it was assumed that the control system has access to an exact full-state measurement. In reality, it is necessary to have a navigation system, composed by sensors and estimators, capable of providing an accurate estimate on the state vector. For the case of rockets, and taking into account the state variables to measured, it is common to use an Inertial Measurement Unit (IMU), composed by accelerometers, gyroscopes, barometers, and magnetometers, and a Global Navigation Satellite System (GNSS) receiver.

The estimator architecture was based on [17]. It is composed by three main filters and a pre-processing unit (PU), according to the scheme in Fig. 6.

Fig. 6
figure 6

Estimator architecture

The pre-processing unit (PU) combines the magnetometer and accelerometer readings, \(\textbf{m}_r\) and \(\textbf{a}_r\), to obtain an indirect measurement on the Euler angles, \(\varvec{\lambda }_r\). Then, the first filter is an Attitude Complementary Filter (ACF), which will use the Euler angles readings and the measured angular rates from the gyroscopes, \(\varvec{\omega }_r\), to provide a filtered attitude estimate, \(\hat{\varvec{\lambda }}\), and an estimate on the bias of the three angular rates, \(\textbf{b}_{\varvec{\omega }}\), to correct the signal from the sensor. The second one is a Position Complementary Filter (PCF), which merges the position readings from the GNSS receiver, translated into the inertial frame, \(\textbf{p}_r\), and the acceleration measurements from the accelerometer to provide an estimate on the velocity vector, \(\hat{\textbf{v}}\). This filter is also self-calibrated since it accounts for the bias in the three acceleration readings, \(\textbf{b}_\textbf{a}\). Finally, a Linear Parameter Estimator (LPE), uses the control inputs, velocities, angular rates and attitude pre-filtered values to give a final estimate on the state vector, \(\hat{\textbf{x}}\), and parameters, \(\hat{\varvec{\zeta }}\).

4.1 ACF

For the ACF, it is assumed that the Euler angles measurement is corrupted by Gaussian white noise, \(\textbf{w}_{\varvec{\lambda }}\), as well as the angular rates readings, \(\textbf{w}_{\varvec{\omega }}\), and that the gyroscope bias is described by a constant term with additional Gaussian white noise. Considering this, the filter is based on the kinematic equations for the Euler angles (5), using directly the Euler angles readings in the process matrices to allow for the use of a linear estimator, in this case a Kalman filter. Its state-space representation follows:

$$\begin{aligned} \dot{\hat{\textbf{x}}}= & {} \begin{bmatrix} 0 &{} 0 &{} 0 &{} -1 &{} -s_{\phi _r}\,t_{\theta _r} &{} -c_{\phi _r}\,t_{\theta _r}\\ 0 &{} 0 &{} 0 &{} 0 &{} -c_{\phi _r} &{} s_{\phi _r}\\ 0 &{} 0 &{} 0 &{} 0 &{} -\displaystyle \frac{s_{\phi _r}}{c_{\theta _r}} &{} -\displaystyle \frac{c_{\phi _r}}{c_{\theta _r}}\\ 0 &{} 0 &{} 0 &{} 0 &{} 0 &{} 0\\ 0 &{} 0 &{} 0 &{} 0 &{} 0 &{} 0\\ 0 &{} 0 &{} 0 &{} 0 &{} 0 &{} 0 \end{bmatrix} \hat{\textbf{x}}+ \begin{bmatrix} 1 &{} s_{\phi _r}\,t_{\theta _r} &{} c_{\phi _r}\,t_{\theta _r}\\ 0 &{} c_{\phi _r} &{} -s_{\phi _r}\\ 0 &{} \displaystyle \frac{s_{\phi _r}}{c_{\theta _r}} &{} \displaystyle \frac{c_{\phi _r}}{c_{\theta _r}}\\ 0 &{} 0 &{} 0\\ 0 &{} 0 &{} 0\\ 0 &{} 0 &{} 0 \end{bmatrix}\varvec{\omega }_r \\{} & {} +\textbf{K}_\textrm{acf}\,(\textbf{y}-\hat{\textbf{y}}),\\ \textbf{x}= & {} \left[ \begin{array}{lll} \varvec{\lambda }&\textbf{b}_{\varvec{\omega }} \end{array}\right] ^T,\hspace{10pt}\textbf{y} = \varvec{\lambda }_r + {\textbf{w}_{\varvec{\lambda }}},\hspace{10pt} \hat{\textbf{y}} = {\hat{\varvec{\lambda }}}. \end{aligned}$$

To calculate the gain matrix \(\textbf{K}_\textrm{acf}\), with dimension \(6\times 3\), the time-invariant equivalent of the system is obtained by choosing the vertical attitude, \(\varvec{\lambda }=\left[ 0\,\,0\,\,0\right] ^T\), to define the process matrices and compute the time-invariant Kalman gains.

4.2 PCF

For the PCF, both the position and acceleration measurements are considered to be corrupted by Gaussian white noise, \(\textbf{w}_\textbf{p}\) and \(\textbf{w}_\textbf{a}\), and the accelerometer bias is also described by a constant term with additional Gaussian white noise. This filter is also kinematic, considering the following equations of motion:

$$\begin{aligned} \dot{\textbf{p}} = \textbf{R}\,{\textbf{v}}\,,\hspace{10pt} \ddot{\textbf{p}} = \textbf{R}\,{\textbf{a}}\,, \end{aligned}$$
(10)

where \(\textbf{p}\) is the position in the inertial frame and \(\textbf{a}\) is the acceleration expressed in the body frame. The state-space representation of the filter is then obtained,

$$\begin{aligned} \dot{\hat{\textbf{x}}}= & {} \begin{bmatrix} \mathbf {0_{3x3}} &{} \mathbf {I_3} &{} \mathbf {0_{3x3}}\\ \mathbf {0_{3x3}} &{} \mathbf {0_{3x3}} &{} -\textbf{R}\\ \mathbf {0_{3x3}} &{} \mathbf {0_{3x3}} &{} \mathbf {0_{3x3}} \end{bmatrix}\hat{\textbf{x}}+ \begin{bmatrix} \mathbf {0_{3x3}}\\ \textbf{R}\\ \mathbf {0_{3x3}} \end{bmatrix}\mathbf {a_r} + \begin{bmatrix} \mathbf {K_1}\\ \mathbf {K_2}\\ \textbf{R}^T\,\mathbf {K_3} \end{bmatrix}(\textbf{y}-\hat{\textbf{y}}),\\ \textbf{x}= & {} \left[ \begin{array}{lll} \textbf{p}&\dot{\textbf{p}}&\mathbf {b_a} \end{array}\right] ^T,\hspace{10pt}\textbf{y} = \textbf{p}_r + \mathbf {w_p},\hspace{10pt} \hat{\textbf{y}} = \hat{\textbf{p}}. \end{aligned}$$

where \(\mathbf {I_3}\) stands for the identity matrix and \(\mathbf {_{3x3}}\) for the matrix of zeros, both of dimension 3 by 3. The rotation matrix \(\textbf{R}\) is calculated using the Euler angles estimate from the ACF (\(\hat{\varvec{\lambda }}\)). The individual gain matrices \(\mathbf {K_1}\), \(\mathbf {K_2}\) and \(\mathbf {K_3}\), each with dimension 3 by 3, can once again be computed considering the vertical attitude time-invariant to define the rotation matrix \(\textbf{R}\), so as to obtain time-invariant Kalman gains.

4.3 LPE

The robustness of the LQR is limited since the controller is designed considering a nominal evolution of model parameters that might considerably differ from the real evolution during the mission. Amongst the model parameters, the ones related with the aerodynamic properties of the rocket are subjected to an higher level of uncertainty, due to the difficulty in obtaining accurate aerodynamic coefficients and derivatives of the rocket for a broad range of velocities and aerodynamic angles. In this way, an online parameter estimator is proposed so that the controller acts on an informed value of the aerodynamic parameters.

The aerodynamic parameters are hidden under the aerodynamic force and moment coefficients. Since a first estimate on these quantities is available using the stored aerodynamic data, a proportional error factor is multiplied in each aerodynamic force and moment, corresponding to the parameters to be estimated.

The estimator design follows along the methodology proposed in [18], where an hovercraft control system is designed based on dynamic parameters identification, which details a generic parameter estimator for time-varying systems, linear in the parameters.

The previously detailed rocket model (section 2.4) is rearranged by including the proportional error factors, \(\delta _{a_x}\), \(\delta _{a_y}\), \(\delta _{a_z}\), \(\delta _{m}\), and \(\delta _{n}\) on the aerodynamic forces and moments, making \({^{B}{\mathbf {F_{a}}}} = \begin{bmatrix} -\overline{q}\, C_A\, S\delta _{a_x}\,&\overline{q}\, C_{Y}\, S\delta _{a_y}\,&-\overline{q}\, C_{N}\, S\delta _{a_z} \end{bmatrix}^T\) and \({^{B}{\mathbf {M_{a}}}} = \begin{bmatrix} 0\,&\overline{q}\, C_mS\, d\delta _m\,&\overline{q}\, C_nS\, d\delta _n \end{bmatrix}^T\), where the aerodynamic rolling moment is discarded due to the additional roll control system. After substituting the rearranged aerodynamic forces and moments in the rocket model, and considering the linearity in the parameters to be estimated, the non-linear differential equations take the form \(\dot{\textbf{x}} = \textbf{f}(\textbf{x},t) + \textbf{G}(\textbf{x},t)\,\varvec{\zeta }\), where \(\textbf{x}=\left[ u\,\,v\,\,w\,\,q\,\,r\,\,\phi \,\,\theta \,\,\psi \right] ^T\) and \(\varvec{\zeta }=\left[ \delta _{a_x}\,\,\delta _{a_y}\,\,\delta _{a_z}\,\,\delta _{m}\,\,\delta _{n}\right] ^T\). Using state augmentation with the parameter vector, \(\varvec{\zeta }\), and assuming full-state measurements, \(\textbf{y}\), are available, this system can be written in state-space form as

$$\begin{aligned} \begin{bmatrix} \dot{\textbf{x}}\\ \dot{\varvec{\zeta }} \end{bmatrix} = \begin{bmatrix} \mathbf {0_{8x8}} &{} \textbf{G}(\textbf{y},t)\\ \mathbf {0_{5x8}} &{} \mathbf {0_{5x5}} \end{bmatrix} \begin{bmatrix} \textbf{x}\\ \varvec{\zeta }\end{bmatrix} + \begin{bmatrix} \textbf{f}(\textbf{y},t)\\ \mathbf {0_{5x1}} \end{bmatrix}\,, \end{aligned}$$
$$\begin{aligned} \textbf{y} = \textbf{C}\,\textbf{x}\,,\hspace{10pt} \textbf{C} = \begin{bmatrix}\mathbf {I_{8}}&\mathbf {0_{8x5}} \end{bmatrix}\,, \end{aligned}$$

in which the full-state measurement assumption allows to regard the system as linear, and the parameters are assumed to be slowly varying. The \(\textbf{G}(\textbf{y},t)\) and \(\textbf{f}(\textbf{y},t)\) matrices are easily obtained using the derived rocket model with the inclusion of the correction factors, and are not here presented to improve readability.

In order to design the estimator for this system, it is necessary for it to be observable. In the reference, it is demonstrated that the system is observable if and only if there exists no unit vector \(\textbf{d}\), with the dimension of the parameter vector, such that \(\int _{t_0}^{t} \textbf{G}(\textbf{y},\sigma )\,d\sigma \cdot \textbf{d} = 0\). Taking the time derivative in both sides and substituting for the rocket dynamics, the equivalent non-observability condition is

$$\begin{aligned} {\left\{ \begin{array}{ll} -m^{-1}\,\overline{q}\,S\,C_A\,d_1 = 0\\ m^{-1}\,\overline{q}\,S\,C_Y\,d_2 = 0\\ -m^{-1}\,\overline{q}\,S\,C_N\,d_3 = 0\\ J^{-1}\,\overline{q}\,S\,d\,C_m\,d_4 = 0\\ J^{-1}\,\overline{q}\,S\,d\,C_n\,d_5 = 0\\ \end{array}\right. } \Leftrightarrow {\left\{ \begin{array}{ll} C_A\,d_1 = 0\\ C_Y\,d_2 = 0\\ C_N\,d_3 = 0\\ C_m\,d_4 = 0\\ C_n\,d_5 = 0\\ \end{array}\right. }, \end{aligned}$$

where \(d_i\), for \(i = {1,2,3,4,5}\), are the components of the unit vector, and the simplification is due to m, J, \(\overline{q}\), d, and S being always different from zero.

It is possible to infer that the system is observable only when the aerodynamic force and moment coefficients are all different from zero, since if one of them is not, the unit vector with \(d_i\) = 1, where i corresponds to component multiplying the null coefficient, satisfies the non-observability condition. However, given a null coefficient, the correspondent correction factor is the unobservable parameter, meaning that estimates can still be obtained for the remaining ones. Nevertheless, to ensure full observability, if the pre-calculation of a given coefficient results in zero, it can be forced to a small non-zero value. After verifying that the system can be made observable, a Kalman filter represents a simple and easily tunable solution for the estimation of the system state, resulting in the following state-space representation for the LPE:

$$\begin{aligned} \begin{bmatrix} \dot{\hat{\textbf{x}}}\\ \varvec{\dot{\hat{\zeta }}} \end{bmatrix} = \begin{bmatrix} \mathbf {0_{8x8}} &{} \textbf{G}(\textbf{y},t)\\ \mathbf {0_{5x8}} &{} \mathbf {0_{5x5}} \end{bmatrix} \begin{bmatrix} \hat{\textbf{x}}\\ \varvec{\hat{\zeta } } \end{bmatrix} + \begin{bmatrix} \textbf{f}(\textbf{y},t)\\ \mathbf {0_{5x1}} \end{bmatrix}+ \textbf{K}_{lpe}\,(\textbf{y}-\textbf{C}\,\hat{\textbf{x}})\,, \end{aligned}$$

4.3.1 Adaptive LQI Control

Resorting to the real-time estimates on the aerodynamic error coefficients, the LQI controller gains can be computed on-board instead of scheduling the pre-calculated gains for each operating point. This is done by rewriting the state-space representation with the inclusion of the estimated parameters, and solving the ARE on-board with the updated state-space models. The rearranged system dynamics matrix, \(\textbf{A}\), can be easily achieved and is not here presented.

5 Simulation Results

5.1 Simulation Environment

To test and validate the proposed ADCS in the complete non-linear model, a realistic simulation model is implemented in MATLAB/Simulink® environment. The model is composed by several subsystems in order to completely transcribe the derived dynamics and kinematics, generate the environmental properties, and compute the model-varying parameters.

The environmental properties are generated by the atmospheric, wind, and gravitational models. The 1976 U.S. standard atmosphere was implemented, which describes the evolution of temperature and pressure with altitude using average annual values, from which density and speed of sound are derived. Wind is introduced through the summation of the average horizontal wind components from the U.S. Naval Research Laboratory horizontal wind model with wind gusts added from the Dryden model, both available as Simulink blocks. Finally, the gravitational model is implemented according to the equations in Sect. 2.3.1.

Several varying model parameters have to be computed during simulation. The ideal thrust force and mass flow rate are predetermined using the propulsion model detailed in Sect. 2.3.2, and the static, atmospheric pressure-dependant thrust component is added during the simulation. The aerodynamic properties, i.e. the aerodynamic derivatives and centre of pressure location, are stored in look-up tables and are selected according to the instant values of the aerodynamic angles and Mach number. The mass properties are also computed during the simulation, including the mass, inertia, and centre of mass, which vary due to the propellant consumption.

The equations of motion used in the simulation environment are the ones presented in Sect. 2.4. It is important to note that some assumptions were used when deriving the model and, although considered valid for design, can have impact on the expected performance, obtained in simulation, when in a real case scenario. Elastic modes might be excited by the control action if the associated frequencies are similar, causing undesired oscillatory behaviour; asymmetries may cause the centre of mass to be dislocated from the x-axis of the body, which imposes additional effort on the control action; and non-linear aerodynamic effects may cause unexpected behaviour, as well as unaccounted effects caused by the rotation of the Earth, such as the Coriolis acceleration.

5.2 ADCS Parameters

In this section, some of the parameters used in the simulation environment are detailed. These include the model used for the actuators, the control system gains, and the covariance matrices obtained for the navigation system.

5.2.1 Actuators’ Model

The actuators’ dynamics are modelled using a continuous time first-order transfer function for each input (\(\mu _p\) and \(\mu _y\)), considering a servo-actuated system. The transfer function is given by

$$\begin{aligned} \mu _r = \frac{1}{\tau \,s + 1}\,\mu \, \end{aligned}$$

where \(\mu _r\) is the actuator angular response and \(\tau\) is the time constant. In addition, servo motors normally have a saturation value for the rotation velocity, which can be modelled by a rate limiter block in Simulink. The time constant and angular velocity limit values were retrieved from typical high grade servo motors, and are equal to \(0.02\,\)s and 1 full rotation per second, respectively.

5.2.2 Control Gains

The tuning of the \(\varvec{\mathcal {Q}}\) and \(\varvec{\mathcal {R}}\) matrices for each mode yielded the time evolution for the controller gains throughout the nominal trajectory detailed in Fig. 7.

Fig. 7
figure 7

Controller gains over time

The gains remain approximately constant given that the tuning matrices were left constant for all operating points, except for the ones associated with the longitudinal mode during the varying pitch section, which were tuned in order to reduce the control effort and avoid saturation.

5.2.3 Estimation Covariances

Each of the individual filters composing the navigation system follows the Kalman filter structure [19], meaning that the tuning parameters are their respective covariance matrices, \(\varvec{\mathcal {Q}}\) and \(\varvec{\mathcal {R}}\). The \(\varvec{\mathcal {Q}}\) corresponds to the covariance of the process noise, and \(\varvec{\mathcal {R}}\) corresponds to the covariance of the measurement noise. The \(\varvec{\mathcal {R}}\) matrices can be derived by referring to the noise properties of the on-board sensors, while the \(\varvec{\mathcal {Q}}\) matrices are iteratively adjusted looking at the simulation results in the realistic environment, yielding

$$\begin{aligned}{} & {} \varvec{\mathcal {Q}}_\textrm{acf} = 10^{-1}\,\mathbf {I_3},\hspace{10pt} \varvec{\mathcal {Q}}_\textrm{pcf} = 10^{-2}\,\mathbf {I_3},\hspace{10pt} \varvec{\mathcal {Q}}_\textrm{lpe} = \begin{bmatrix} 10^{-2}\,\mathbf {I_8} &{} \mathbf {0_{8x5}}\\ \mathbf {0_{5x8}} &{} 10\,\mathbf {I_5} \end{bmatrix}, \\{} & {} \varvec{\mathcal {R}}_\textrm{acf} = \mathbf {I_3},\hspace{10pt} \varvec{\mathcal {R}}_\textrm{pcf} = 4\,\mathbf {I_3},\hspace{10pt} \varvec{\mathcal {R}}_\textrm{lpe} = 10\,\mathbf {I_8}. \end{aligned}$$

5.3 Navigation System

The navigation system is tested and is able to reject the noise introduced by the sensors, remove the bias, and provide an accurate estimate on the state of the rocket. Figure 8 presents the pitch angle and pitch rate estimation by the ACF, while Fig. 9 presents the crossrange position and longitudinal velocity estimation by the PCF, both as exemplification of the performance of the system.

Fig. 8
figure 8

Pitch angle a and pitch rate b estimation

Fig. 9
figure 9

Crossrange position a and longitudinal velocity b estimation

The linear parameter estimator is also tested in simulation, by inducing errors in the aerodynamic coefficients, and is able to correctly estimate the parameters. Figure 10 presents the results for a simulation in which errors were induced in the aerodynamic coefficients associated with pitch plane motion (\(C_A\), \(C_N\), and \(C_m\)). The affected parameters (\(\delta _{a_x}\), \(\delta _{a_z}\) and \(\delta _{m}\)) are seen to correctly converge to the expected values and the associated estimation errors for the aerodynamic forces and moments are minimised.

Fig. 10
figure 10

LPE simulation results—parameter estimation (a) and estimation errors (b)

5.4 LQI Control

The LQI controller is implemented in the simulation model and tested by adding wind, with and without gusts, as external perturbation. Table 4 displays the results in terms of attitude tracking performance and control effort, not only for the LQI controller, but also for a tested PID controller for comparison.

Table 4 Tracking error and control effort

It is noted that the LQI controller provides better attitude tracking for the same control effort with respect to the PID. In the yaw plane, the results for the PID are significantly worse since it is very affected by the initial wind perturbation. The step response is also analysed (Tab. 5).

Table 5 Step response performance

Once again the LQI displays satisfactory performance, close to the design values (Tab. 3), and significantly better than the classical PID. Additionally, a robustness analysis is carried out, in which the model parameters are varied in percentage. For the assumed parameter uncertainties, the LQI controller shows high robustness.

5.4.1 Adaptive LQI Control

Due to the high robustness of the non-adaptive LQI controller, the adaptive version is not able to produce significant performance improvements.

5.5 Complete ADCS

The complete ADCS is tested by integrating the attitude control and navigation systems. Table 6 details the attitude tracking performance and the control effort with wind gusts present, in comparison with the results for the control system alone without sensor noise.

Table 6 ADCS simulation results

As expected, there is a performance decrease. However, it is still satisfactory.

5.5.1 Sensitivity Analysis

Finally, a sensitivity analysis was performed to determine the robustness of the system to model uncertainties. Several system parameters, including dry mass, inertia, Thrust, centre of mass position, and aerodynamic coefficients, were altered independently, inside admissible ranges in terms of percentage of the original value:

$$\begin{aligned} T:\pm 5\%\,\hspace{10pt} m_\textrm{dry}:\pm 10\%\, \hspace{10pt}x_\textrm{cm},\,J_t,\,C_A,\,C_N,\,C_Y:\pm 20\% \end{aligned}$$

The system showed sufficient robustness, being able to stabilise the plant for all the variations under study. The parameter which demonstrated the highest influence in the performance of the control system was the position of the centre of mass (\(x_{cm}\)), with the results shown in Table 7.

Table 7 Attitude tracking performance for different \(x_{cm}\)

A lower value, meaning a position closer to the tip of the rocket, causes the moment arm for the thrust vector actuation to be higher, which increases the control authority. At the same time, the natural instability of the rocket reduces. In this way, the tracking performance increases when the centre of mass moves closer to the tip, while the control effort decreases.

6 Conclusions

With the conclusion of this work, it is possible to state that the primary goal has been achieved: the successful design of an attitude determination and control system applicable to sounding rockets with thrust vectoring. The design process was described in a generic way to ensure that the system can be easily applied to different vehicles under the same category. Nevertheless, the future implementation of the system in a student-built sounding rocket was always taken into account, as it was the initial motivation behind this work.

As future work, it would be of interest to develop non-linear controllers for the attitude control problem in order to compare the performance of said controllers with the developed ones. Particularly, the designed linear parameter estimator could be used for a non-linear control system that requires accurate information on the aerodynamic forces and moments to guarantee its correct functioning. Moreover, both the developed simulation model and navigation system can be verified and validated using real flight data from sounding rockets launched by RED. In fact, the simulation environment shall be improved by including phenomena yet to be modelled, such as elastic modes, non-linear aerodynamic effects, the curvature and rotation of the Earth, and body asymmetries, to further verify the system before implementation in a real case scenario.

Finally, RED is currently developing small-scale prototypes to test the TVC technology and the associated navigation and control systems. In this way, it is intended to implement the techniques in here developed to such prototypes and to analyse all the results coming from test campaigns.