Keywords

1 Introduction

The Human Space Mission is providing a great deal of opportunities in space research activities which are oriented toward the design and development of space stations. Space stations are the permanent manned presence in space. Space stations always met with the problem of low-cost transportation. This can be achieved by using an assured crew reentry vehicle [13]. In this paper, the attitude control of an assured crew reentry vehicle is illustrated. An attitude controller is planned to track the reference attitude obtained from the trajectory controller and navigational system of an assured crew reentry vehicle. This allows the vehicle to experience the aerodynamic force required to follow the reference trajectory path. The trajectory controller computes the attitude required and attitude controller computes the torque required to generate the attitude.

The controller tuning is complicated and in recent past, many modern heuristic optimization algorithms like genetic algorithm, simulated annealing, tabu search, swarm intelligence techniques, like particle swarm optimization, bacterial foraging, bee colony optimization, fire fly algorithm are investigated [4]. Heuristic algorithms are techniques used to obtain global optimal solution [5]. Genetic Algorithm has been used extensively to obtain the conventional PID controller due to its capability of not getting struck in the local minima. Genetic algorithm has been implemented for many processes like control of reverse osmosis [6], single link flexible manipulator in vertical motion [7], etc. Various performance measures like minimum rise time, settling time, overshoot, integral absolute error, integral square error, and integral time absolute error has been considered as the objective function by many authors [8].

The attitude controller is designed using genetic algorithm-based sliding mode controller. quaternions are used to describe the kinematics of the ACRV [9, 10]. Finally, thrusters are incorporated to provide the torque required by the attitude controller. These are modulated using a PWPF thruster modulator. Simulations are performed by using the trajectory controller output as reference.

Section 2 discusses about the coordinate systems highlighting the coordinate transformation followed by the Quartenion formulations. Section 4 presents the mathematical model of ACRV and Sects. 5 and 6 discusses in detail about the controller design and optimization of the parameters using genetic algorithm-based sliding mode controller followed by the Design of Thrusters. Finally the simulation results are presented.

2 Coordinate Systems

To describe the model of an assured crew reentry vehicle, a suitable coordinate system is to be adopted. The various coordinate systems are:

  • Inertial Coordinate System: System is having the origin at the Earths center, with the X and Y axis in the equatorial plane and the Z axis aligned with the planet polar axis, positive toward the south.

  • Local Geocentric System: System is having the Z axis along the line through the center of mass of the body, positive toward the Earth center; X axis is orthogonal to Z axis and positive toward the north and Y axis completes the right-handed orthogonal frame.

  • Wind Axis System: System is having the X axis along velocity vector corresponding to the local geocentric frame. The Z axis is aligned with the lift force, with opposite direction and Y axis completes the right-handed orthogonal frame.

  • Body Axes System: System will be having X axis along the geometric longitudinal axis of the body, positive toward the capsule nose and Y axis is along symmetry plane of the body pointing downwards entry and perpendicular to the X axis. The Z axis completes the right-handed orthogonal frame.

For obtaining the suitable co-ordinate system for describing the assured crew reentry vehicle dynamics, various coordinate transformations are done.

2.1 Coordinate Transformations

\(\alpha ,\beta ,\sigma\) are the trajectory controller outputs. The other angular values required for the generation of quaternions are provided by the navigational system. Various coordinate transformations are done to achieve the required input parameters. The coordinate transformations are:

  • The transformation matrix for transforming the inertial coordinates to local geocentric coordinates is:

    $$G = \left[ {\begin{array}{*{20}c} { - \sin (\phi )*\cos (B)} & { - \sin (\phi )*\sin (B)} & { - \cos (\phi )} \\ {\sin (B)} & { - \cos (B)} & 0 \\ { - \cos (\phi )*\cos (B)} & { - \cos (\phi )*\sin (B)} & {\sin (\phi )} \\ \end{array} } \right]$$
    (1)
  • The transformation matrix for transforming local geocentric coordinates to wind axis coordinate system is:

    $$\begin{aligned} W & = \left[ {\begin{array}{*{20}c} {\cos (\gamma )\cos (\phi )} \\ {( - \sin (\phi )\cos (\sigma )) + (\sin (\gamma )\cos (\phi )\sin (\sigma ))} \\ {( - \sin (\phi )\sin (\sigma )) + (\sin (\gamma )\cos (\phi )\cos (\sigma ))} \\ \end{array} } \right. \\ & \quad \;\left. {\begin{array}{*{20}c} {\cos (\gamma )\sin (\phi )} & { - \sin (\gamma )} \\ {(\cos (\phi )\cos (\sigma )) + (\sin (\gamma )\sin (\phi )\sin (\sigma ))} & {\cos (\gamma )\sin (\sigma )} \\ {( - \cos (\phi )\sin (\sigma )) + (\sin (\gamma )\sin (\phi )\cos (\sigma ))} & {\cos (\gamma )\cos (\sigma )} \\ \end{array} } \right] \\ \end{aligned}$$
    (2)
  • The transformation matrix for transforming wind axis coordinate system to body axis coordinate system is:

    $$B = \left[ {\begin{array}{*{20}c} {\cos (\alpha )*\cos (\beta )} & {\sin (\beta )} & {\sin (\alpha )*\cos (\beta )} \\ { - \sin (\beta )*\cos (\alpha )} & {\cos (\beta )} & { - \sin (\beta )*\sin (\alpha )} \\ { - \sin (\alpha )} & 0 & {\cos (\alpha )} \\ \end{array} } \right]$$
    (3)

The direction cosine matrix ‘E’ is obtained as:

$$E = G*W*{\text{inv}}(B) = \left[ {\begin{array}{*{20}c} {e11} & {e12} & {e13} \\ {e21} & {e22} & {e23} \\ {e31} & {e32} & {e33} \\ \end{array} } \right]$$
(4)

From the direction cosine matrix, the commanded quaternions for the ACRV are generated.

3 Quaternion Formulation

Quaternions are the most effective method for identifying the rotational motion. Quaternions are the vectors in 4D space algebra. Instead of the trigonometric functions of Euler angles, the quaternion uses algebraic relations. Hence quicker computation is achieved and use of quaternions also helps to eliminate the possibility of a singularity problem [11, 12].

From the direction cosine matrix as in Eq. (4), the commanded quaternions are calculated as follows:

$$q_{4c} = 0.5*\sqrt {1 + e11 + e22 + e33}$$
(5)
$$q_{1c} = \left( {\frac{1}{{4*q_{4c} }}} \right)(e23 - e32)$$
(6)
$$q_{2c} = \left( {\frac{1}{{4*q_{4c} }}} \right)(e31 - e13)$$
(7)
$$q_{3c} = \left( {\frac{1}{{4*q_{4c} }}} \right)(e12 - e21)$$
(8)

The quaternions have two parts, i.e., a quaternion magnitude given by Eq. (5) and quaternion orientation represented by Eqs. (6), (7), and (8).

The reference angular velocities can also be computed from the reference quaternions. It is obtained as:

$$\hat{\omega} = 2*\Omega(\hat{q}_{c})^{\text{T}} * \dot{\hat{q}}_{c}$$
(9)

where

$$q_{c} = \left[ {\begin{array}{*{20}c} {q_{1c} } & {q_{2c} } & {q_{3c} } & {q_{{4_{c} }} } \\ \end{array} } \right]^{\text{T}} .$$

4 Mathematical Model of ACRV

Mathematical model of ACRV is derived from the Rigid Body Dynamic Equation and then the Rigid Body Kinematic Equation [13, 14].

4.1 ACRV-dynamic Equation

$$J*\dot{\omega } + S(\omega )*J*\omega = M_{t} + M_{a}$$
(10)

where

$$J = J_{0} +\Delta J\quad {\text{and}}\quad \omega = (\omega_{x} ,\omega_{y} ,\omega_{z} )^{\text{T}}$$
(11)

The skew symmetric matrix is given by,

$$S(\omega ) = \left( {\begin{array}{*{20}c} 0 & { - \omega_{z} } & {\omega_{y} } \\ {\omega_{z} } & 0 & { - \omega_{x} } \\ { - \omega_{y} } & {\omega_{x} } & 0 \\ \end{array} } \right)$$
(12)

4.2 ACRV-kinematic Equation

The kinematic description of the rigid body motion involves three parameters known as the Euler angles. But in case of large angle maneuvers, Euler angles can exhibit singularities. In such cases quaternions are also used. The quaternion parameters are defined as,

$$q = \left[ {\begin{array}{*{20}c} {q_{1} } & {q_{2} } & {q_{3} } & {q_{4} } \\ \end{array} } \right]^{\text{T}}$$
(13)

where \(q_{1}\), \(q_{2}\) and \(q_{3}\) represents the angular part and \(q_{4}\) represents the magnitude part.

The rigid body kinematic equation is given by,

$$\dot{q} = 0.5*\Omega (q)*\omega ,$$
(14)

where

$$\Omega (q) = \left[ {\begin{array}{*{20}c} {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]$$

5 Controller Design

The attitude controller for the ACRV will track the capsule along the prescribed path.

The results of the trajectory controller are the commanded angles \(\alpha_{c} ,\beta_{c} ,\sigma_{c}\) [13, 14]. The commanded angles, along with the data composed from the navigational systems are used to generate the reference angular rates using Eq. (9).

For obtaining a sliding mode controller [13], consider the system

$$\dot{x} = Ax + Bu,\quad x \in R_{1} ,\quad u \in R^{3}$$

Let \(s :R_{1} *[0,\infty )\) be a continuously differentiable map and define a related sliding manifold as in Eq. (15). Let the function g be defined by Eq. (16).

$$S = \{ (x,t) \in R_{1} *[0,\infty ) :s(x,t) = 0\} .$$
(15)
$$p(x,u,t) = \frac{\partial }{\partial x}s(x,t) + \frac{\partial }{\partial x}s(x,t)[Ax + Bu]$$
(16)

The system of ordinary differential equations is expressed as:

$$\begin{aligned} \dot{x} & = Ax + Bu \\ \zeta *\dot{u} & = g(x,u,t),\quad \zeta < 0 \\ \end{aligned}$$
(17)

For obtaining the solution of Eq. (17), a theorem is stated that for any pair \((x,t) \in I\), the unique solution \(u^{*} (x,t)\) of the algebraic equation \(g(x,u,t) = 0\) is called equivalent control for the problem.

It is possible to show that uniquely the equivalent control is,

$$u^{*} (x,t) = - \left[ {\frac{\partial }{\partial x}s(x,t)B} \right]^{ - 1} \times \left[ {\frac{\partial }{\partial t}s(x,t) + \frac{\partial }{\partial x}s(x,t)A(x)x} \right]$$
(18)

Let, \(\hat{x} = (\hat{q}^{\text{T}} ,\hat{\omega }^{\text{T}} )^{\text{T}}\) be a reference state attitude for the reentry vehicle. The problem can be formulated as to design a feedback controller in such a way that, the error vector, \(e = \hat{x} - x\) satisfies Eq. (19), for a given \(\beta > 0,\delta > 0\).

$$\left\| e \right\| \le \delta + A*{e}^{ - \beta t}$$
(19)

where A is a constant depending on the data. To solve the attitude control problem, the sliding surface s is defined as in Eq. (20).

$$s(x,t) = H(q)[e - f(x_{0} ,t)]$$
(20)

where, \(x_{0} = x(0)\) and \(H(q)\) is a matrix of suitable dimensions to be chosen. Let,

$$H(q) = \left[ {\begin{array}{*{20}c} {H^{\prime}_{1} *\Omega ^{\text{T}} (q)} & {H_{2} } \\ \end{array} } \right]$$
(21)

where \(H_{2} *J\) is nonsingular. The \(f(x_{0} ,t)\) in Eq. (20) is given by,

$$f(x_{0} ,t) = {e}^{Ct} *e$$
(22)

where C is a stability matrix. Now a theorem can be stated as follows to define the equivalent control [10, 13].

Theorem

Let \(x_{0} \in R_{1}\) be given. Assume that, \(Re \lambda_{\hbox{min} } (H_{2} J^{ - 1} ) > 0\) and \(H^{\prime}_{1}\) be a matrix such that \(H_{2}^{ - 1} \times H^{\prime}_{1}\) is symmetric and positive definite. Let, \(Re \lambda_{\hbox{max} } (C) < - \lambda_{\hbox{min} } (H_{2}^{ - 1} \times H^{\prime}_{1} )\) then there exists an \(\xi_{0} > 0\) such that the solution of [x, u] satisfying the initial conditions and \(\hat{x}(t) - x(t,\xi ) < \delta + A*{e}^{ - \beta t}\).

Then the controller is obtained as in Eq. (23).

$$u(t,\xi ) = (1/\xi )\left[ {\begin{array}{*{20}c} {H^{\prime}_{1}\Omega ^{\text{T}} (q)} & {H_{2} } \\ \end{array} } \right] \times \left[ {\hat{x}(t) - x(t,\xi ) - {e}^{Ct} \left( {\hat{x}_{0} - x_{0} } \right)} \right] + u_{0}$$
(23)

where, \(t \ge 0\) and \(A\) are \(\beta\) positive constants depending on \(H^{\prime}_{1} ,H_{2} ,C\).

For the proposed model of ACRV, the constant matrices are selected as, \(C = {\text{diag}}(C_{q} ,C_{w} )\), \(H^{\prime}_{1} = 10I_{3}\), \(H_{2} = {\text{diag}}(100,50,50)\) \(C_{q} = - 0.1*I_{4}\), \(C_{\omega } = - 0.1*I_{3}\), \(\zeta = 0.001\). The initial conditions are selected as;

$$\begin{aligned} \hat{q}_{0} & = (0.7272,0.1207, - 0.6426, - 0.2091) \\ q_{0} & = (0.7268,0.14, - 0.6274, - 0.2419) \\ \hat{\omega }_{0} & = (0.0008,0.001, - 0.002),\quad \omega_{0} = (0,0,0) \\ \end{aligned}$$

For the proposed model, thrusters are considered to provide the torque required by the attitude controller.

6 Multi-objective Genetic Algorithm-Based Sliding Mode Controller

The genetic algorithms are an evolutionary optimization technique which can find the global optimal solution in complex multidimensional search space. It is an iterative and population-based algorithm. It involves minimization or maximization of an objective function and determination of the parameters of interest.

The algorithm of genetic algorithm is as follows

Step-1:

Initialize the parameters. In the proposed work, seven parameters are considered and an initial population is created.

Step-2:

Compute the objective function.

Step-3:

Check for stall limits or max Generation.

  1. 1.

    Reproduce the next generation

    • Crossover operation

    • Mutation operation

  2. 2.

    Compute objective function

  3. 3.

    Selection of the offspring for the next generation using Roulett wheel.

The multi-objective function used to obtain the optimal controller parameters so as to minimize is given by

$$\begin{aligned} J & = \hbox{min} \left\{ {0.33*{\text{ISE}}({\text{Bank Angle}}) + 0.33*{\text{ISE (Angle of Attack}}({\text{degree}}))} \right. \\ & \quad \quad \quad \;\left. { + 0.33*{\text{ISE}}({\text{Sideslip Angle}}({\text{degree}}))} \right\} \\ \end{aligned}$$

Controller parameter tuned using genetic algorithm

$$C = \left[ {\begin{array}{*{20}c} {0.3566} & 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & {0.100} & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & {0.3863} & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & {0.2528} & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & {0.597} & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & {0.100} & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & {0.2406} \\ \end{array} } \right]$$

7 Design of Thrusters

The output of the attitude controller is provided to the thrusters, which will be modulated. The thrusters provided are based on the pulse width pulse frequency (PWPF) technique [15]. The command inputs to the controller and the output are continuous in nature. The actual control for operating the thrusters for steering the capsule along the prescribed path is in the pulse mode. Hence modulators are used. They will generate the pulsed mode output. The modulator scheme proposed has an integrator and a nonlinear element as in Fig. 1.

Fig. 1
figure 1

Modulator scheme

8 Simulation Results

To check for robustness, the simulations are carried out in the developed model in the presence of aerodynamic disturbance uncertainties. The simulation results are shown in Figs. 2, 3 and 4.

Fig. 2
figure 2

Sideslip angle of multi-objective genetic algorithm-based sliding mode control

Fig. 3
figure 3

Angle of attack of multi-objective genetic algorithm-based sliding mode control

Fig. 4
figure 4

Bank angle of multi-objective genetic algorithm-based sliding mode control

The side slip angle error in Fig. 2 depicts that, the error value of multi-objective genetic algorithm-based sliding mode control method is much close to zero and is having fewer disturbances.

Tracking of angle of attack for a commanded value is done smoothly with very less amount of ripples and reduced disturbances, when the controller is a genetic algorithm-based sliding mode control. This shown in Fig. 3.

In Fig. 4, it is seen that, the control variable bank angle error and the amount of disturbance is also reduced when the controller is multi-objective genetic algorithm-based sliding mode control.

9 Conclusions

An attitude control system is formulated for a reentry vehicle. The attitude control law is based on multi-objective genetic algorithm-based sliding mode control. The objective function is formulated using the minimization function of Integral Square Error including side slip angle, angle of attack, and bank angle. The step-by-step procedure involved in multi-objective controller is reducing the error in side slip angle, angle of attack and bank angle considerably.