<<

Trajectory Optimisation with Evolutionary-Based Initialisation

Christie Alisa Maddock, Edmondo Minisci Aerospace Centre of Excellence Department of Mechanical & Aerospace Engineering University of Strathclyde Glasgow G1 1XJ, [email protected], [email protected]

Abstract— In this paper, an evolutionary-based initialisation de-orbiting manoeuvres in space. Coupled with changes in method is proposed based on Adaptive Inflationary Differential operation, such as switching from an air-breathing engine to Evolution algorithm, which is used in conjunction with a a closed-intake engine or vehicle stage separations, the deterministic local optimisation algorithm to efficiently identify clusters of optimal solutions. The approach is applied to software models must be designed to handle discontinuities. an ascent trajectory for a single stage to spaceplane, The design of spaceplane mission delivering a payload employing a rocket-based combine cycle propulsion system. The to a specified orbit and re-entering is in itself a multiphase problem is decomposed first into flight phases, based on user problem. Across the entire mission, assuming a returnable defined criteria such as a propulsion cycle change translating vehicle, the division is similar to an with to different mathematical system models, and subsequently transcribed into a multi-shooting NLP problem. Examining the take-off, ascent, operations (e.g., payload delivery), re-entry results based on 10 independent runs of the approach, it can be and runway . The two transatmospheric trajectories seen that in all cases the method converges to clusters of feasible can be further divided in multiple segments; the elements solutions. In 40% of the cases, the AIDEA-based initialisation defining the problem can differ though disciplinary models found a better solution compared to a heuristic approach (e.g., propulsion modes for a hybrid engine, or in a multi- using constant control for each phase with a single shooting transcription (representing an expert user). The problem was stage propulsion system), problem objectives and constraints, run using randomly generated control laws, only 2/20 cases and level of fidelity needed within the models. To allow such converged, both times with a less optimal solution compared to flexibility in the design, the simulation needs to be structured the baseline heuristic approach and AIDEA. in multiple phases, with interchangeable disciplinary models, plus mission objectives and constraints. The approach herein I.INTRODUCTION has been designed to allow each phase to define the set of One forerunner for the next generation of space access models used and all the variables involved in the parametri- vehicles are . Spaceplanes operate both as an sation of the controls and propagation of the trajectory. The aircraft, taking advantage of the atmosphere at low altitudes continuity between phases is guaranteed at convergence of where, for example, air-breathing engines can be used along the optimisation process by the optimiser and the problem with lifting surfaces, as a rocket at higher altitudes where the formulation through constraints functions. atmosphere is less dense, and as a in orbit. This The development of methods presented here are part of a concept offers mass savings due to air-breathing engines, larger initiative to develop an integrated, multi-disciplinary which reduces the need for on-board oxygen, and allow more design platform for quickly assessing and optimising con- control into the flight path and therefore the that can ceptual vehicle design and performance for future space be reached from a given take-off and landing site as well as access vehicles, in particular single and multi-stage reusable a wider choice in the site, or , itself. vehicles. The trajectory optimisation solves for an open loop While a single stage to orbit offers full re-usability of control scheme using a multi-phase approach for the configu- the vehicle, it is still largely in the development stage, with ration implemented with a direct multi-shooting transcription many of the key technologies still unproven and also comes method. A set of first guesses are generated using the in- with a cost of lower payload fraction [1]. ’ house Adaptive Inflationary Differential Evolution (AIDEA) vehicle is currently under research and development, algorithm [2], which focuses on exploration, followed by a with a proposed test flight in 2025. Multi-stage spaceplanes local optimisation of candidate solutions using a derivative offer a more immediate time to market though often at a based method for non-linear, constrained problems using cost of partial expendability of parts. and S3 a fixed time step integrator. The trajectories are then re- SOAR are two examples which use a carrier subsonic aircraft propagated with the locally optimal control laws using a to launch a smaller spaceplane. Orbital ATK Pegasus is a variable step numerical integrator with lower tolerances multi-stage rocket launched from an aircraft that has been (higher accuracy) to ensure the feasibility of the solutions. operational since 1990s. The results for the first guess using AIDEA are compared From a design point of view, these vehicles are highly against a phase-based single shooting method using an user complex systems operating across very different environ- supplied control law based on educated guessing. ments from low-altitude subsonic flight to high thermal Results are presented for a test case of conceptual single loads during high altitude re-entry, to orbital insertion and stage to orbit spaceplane optimising the ascent trajectory for a payload delivery mission to a 100 km altitude, circular, subject to equatorial orbit. The objective function is the maximisation of the payload mass delivered to an orbit, with equality xi,k = F ([ti−1,k, ti,k], xi−1,k), constraints on the final position and velocity vectors. Using ui−1,k = ui,k, nc 0 AIDEA for the first guess generation has proved robust and x1,k = x(tn+1,k−1), effective at finding sets of feasible, locally optimal solutions u1,k = un+1,k−1, which can be used to understand the trade-offs between 0 nc performance and vehicle design. c(x(t), u(t)) ≤ 0, t ∈ [t0, tf ] g(x , un,k) ≤ 0, n,k nc II.OPTIMISATIONAPPROACH ω(x0,1, xn,np ) = 0 The optimisation algorithms and approach are shown for i = 1, ..., n − 1, k = 1, ..., n and ∆t = t − t . below, describing the transcription method, based on direct p i,k i+1,k i,k Path constraints are evaluated at a discrete set of points based multi-shooting transcription and flight mission decomposi- n,k in time, and g(xn,k, u ) are the inequality constraints for tion, the evolutionary-based initialisation using AIDEA, and nc phase switching. the local derivative-based optimisation and refinement step. The resulting optimisation problem is usually handled via standard derivative-based methods, requiring a trial-and-error A. Transcription approach by an knowledgeable or expert user to find a The optimal control problem is transcribed into an nonlin- suitable starting point, i.e., an initial solution that can produce ear programming problem by using a multi-phase, multiple- a near-feasible solution that will allow the local deterministic shooting approach. The mission is initially divided into np optimiser to converge. In this respect, the possibility to use user-defined phases. Within each phase, the time interval is evolutionary algorithms to find a suitable starting point is further divided into n multiple shooting segments. explored in this paper. Using an evolutionary approach also has the benefit of producing multiple first guesses as well as np n−1 ∪k=1 ∪i=0 [ti,k, ti+1,k] (1) clustering information on the archived solution sets.

With each interval [ti,k, ti+1,k], the control is further discre- B. Adaptive Inflationary Differential Evolution Algorithm i,k i,k tised into nc control nodes {u , ..., u } and collocated on 0 nc The creation of the algorithm stemmed from the idea Tchebycheff points in time. to create new hybrid algorithms that take elements from Continuity constraints on the control and states are im- different approaches and use them as building blocks for posed, a new algorithm. Following this approach, one of the co- x = F ([t , t ], x )  authors [3] first co-proposed the Inflationary Differential i,k i−1,k i,k i−1,k for k = 1, ..., n (2) ui−1,k = ui,k p Evolution Algorithm (IDEA) in 2011, which combines dif- nc 0 ferential evolution (DE) [4] with the restarting procedure of Monotonic Basin Hopping (MBH) [5] algorithm. IDEA x = x(t )  1,k n+1,k−1 for k = 2, ..., n (3) showed very good results when applied to problems with a u1,k = un+1,k−1 p 0 nc single or multi-funnel landscape. However, its performance was found to depend on the parameters controlling both the where F ([t , t ], x ) is the final state of the nu- i−1,k i,k i−1,k convergence of DE and MBH, and the inflationary stopping merical integration on the interval [t , t ] with initial i−1,k i,k criterion used to terminate the DE search. In particular, conditions x . This approach increases the degree of i−1,k the DE performance is strongly influenced by the crossover freedom of the optimisation process reducing the sensitivity probability CR and the differential weight F whose best of the overall problem to its variables although at a cost of settings are heavily problem dependent [6]. This led to the a steep increase in the number of optimisation variables. development of Adaptive-IDEA, or AIDEA, which uses a The optimisation variables are therefore: probabilistic, Parzen-based kernel approach to automatically • The initial state vector of each shooting segment within adapt the values of both CR and F during the search process every phase (excluding the first segment of the first [2]. Tested on several engineering problems, AIDEA showed phase) xi,k both good exploratory and local search performance, making • The control nodes of each shooting segment it a suitable approach for the initialisation of spaceplane {ui,k, ..., ui,k} 0 nc trajectories. • The time of flight for each shooting segment ∆ti,k The general procedure for the AIDEA used in this paper The discretised optimisation problem is defined as is: 1) The optimisation procedure starts by setting values of: np n−1 X X i,k npop, the maximum number of local restarts, iunmax, min φ(xn,np ) + ∆ti,kf0(xi,k, uj ) {ui,k},{x },{∆t } the size of the convergence box, tol , ρ , and j i,k i,k k=1 i=0 conv A,max (4) δc; and by initialising the population. 2) Then the joint PDF for CR and F , CRFp, is initialised has an additional parameter to be adjusted: the threshold on to be a uniform distribution. At this point, the actual the minimum expected improvement of the cost function. optimisation loop starts by sampling the two vectors This threshold is used to limit the updating of CR, a failsafe CRk and Fk, where k is the current iteration. procedure that has proven to improve the robustness of 3) DE is run drawing probabilistically a value for F and the algorithm. For a complete description of the original CR from CRFp, and CRFp is updated on the basis algorithm, see [2], [8]. of the improvement of the individual using the drawn values of F and CR. C. User Defined Constant Control Initialisation Procedure 4) At this point, A first guess solution can be generated based a phase- a) if the population contracts below the predefined based single shooting method. A control scheme is defined threshold, a local optimiser from current mini- by the user which are linearly interpolated within each phase. mum is run, and at the end of local optimisation, For the test case here, a constant set of controls are used b) if the local optimiser failed to improve the value for each phase. A set of event functions are set, based on of fmin more than iunmax times, the population optional user defined conditions, the upper and lower bounds is restarted globally and iun is set to 0, otherwise, for the states for each phase and the final state. When an the population is restarted within a local bubble event condition is triggered, the integration for that phase and iun = iun + 1. is stopped, with the final state from that phase used as the 5) At this point, initial state for the next phase. a) if the population is re-initialised, the loop restarts from the initialisation of CRFp, D. Evolutionary-based Initialisation Optimisation Proce- b) otherwise just the DE loop restarts. dure 6) As a terminal criterion, the algorithms stops if the 1) As AIDEA can only handle unconstrained optimisa- maximum number of function evaluations, nfeval,max, tion problems, the constrained problem in (4) is first has been performed. converted into an unconstrained one.

In particular, the initialisation of the CRFp to an uniform np n−1 distribution is done by building a regular mesh with (nk + X X i,k min φ(xn,np ) + ∆ti,kf0(uj ) {ui,k},{T } 1) × (nk + 1) points (where nk is a predefined value) in the j i,k k=1 i=0 space CR ∈ [0.5, 0.99] × F ∈ [0.1, 1]. Note, this approach X i−1,k i,k +wα u − u and space definitions are different from the original AIDEA. nc 0 (5) A Gaussian kernel is then allocated on each node and the X 1,k n+1,k−1 +wα u − u PDF is built by Parzen approach [7]. A step change value, 0 nc X X X  dd is linked to each kernel (row of CRFp) and its initial value +wβ ca + ca + ωa is set = 0. npop values of CR and F are sampled from the Parzen distribution and each couple of CR and F values where w are weights, and ca, ga and ωa are the active is associated to one element of the population and used to inequality constraints. Note that equality constraints create the offspring on the basis of the chosen strategy. enforcing matching of the state vectors between the During the optimisation, the location of the kernels is segments is not considered as during the initialisa- updated on the basis of the obtained results. More in details, tion phase the trajectory is propagated using single- to update the matrix containing the location of kernel centres shooting direct transcription approach (using the single (CRFp) after that rows of CRFp are sorted on the basis of shooting integration approach in Section II-C). the associated value of dd, if the objective function of the 2) Within AIDEA, for each iteration of the underlying DE offspring has a value that is strictly lees then the parents the current, best solution is saved into an archive Abest (it is supposed a minimization problems) then the element along with the best individual in the population found of the sorted CRFp are sequentially evaluated and the first with a local search before a local or global restart is time that the associated dd value of the row is less than the initiated. difference between the objective function of the parent and 3) At the end of a run of AIDEA, the final population is that of the offspring then the F value used to operate on added to the archive Abest. the individual xi,k substitutes the element CRFp,2,j,k. The 4) All the solutions in the archive Abest are clustered CR value used to operate on the individual xi,k substitutes on the basis of the Euclidean distance in the search the element CRFp,1,j,k only if the difference between parent space. The clusters are then ranked on the basis of and offspring is greater than a predefined threshold CRC. the performance of best solution within the cluster, The different approach for updating the CR coordinate of where the first cluster, Cbest,1, contains the overall best the kernels is meant to dump the learning of the crossover solution found by AIDEA during that run. to avoid the too fast convergence toward the extremes of the 5) The best solution contained in each one of the first allowed range that can occur in some cases. Note that, as for NC,r clusters is then optimised by a gradient-based other self-adaptive schemes, the adaptive version of IDEA method considering the problem as formulated in (4). III.SPACEPLANESYSTEMMODELS D. Propulsion The propulsion system is assumed to be a rocket-based In this section, mathematical models are presented for combine cycle engine with two distinct modes of operation, the vehicle design and operation of a single-stage-to-orbit modelled as two different engines with an instantaneous (SSTO) spaceplane. The models are divided by discipline: switching mechanism. vehicle mass and configuration, aerodynamics and propul- The rocket cycle is modelled based on Tsiolkovsky rocket sion, environment models for Earth including dimensions, equations. The present configuration used in the test case gravitational field and atmospheric model, and the flight uses LOX/LH2 rocket engines with an I of 450 s. The fuel dynamics and control. sp mixture ratio is assumed constant and the two propellants are treated as a single mass flow m˙ p. A throttle control A. Vehicle Model τ ∈ [0, 1] is added, which dictates the fraction of maximum available thrust applied and fuel mass flow (and therefore The model configuration is based on the CFASTT-1 con- consumption). A simplifying assumption is made that the ceptual test vehicle [9], which has a gross take-off mass of mass flow varies linearly with thrust. The maximum total 260 tons. The design of the vehicle is similar in scale and thrust in a vacuum is set at FT 0,max = 4 MN. The function to Reaction Engines’ Skylon C1 SSTO vehicle [10], instantaneous thrust and mass flow rate are then calculated and was designed as an open test case to examine alternate as, vehicle configurations and aerodynamic properties. FT 0,max m˙ p = τ (7a) g0Isp B. Environment FT,h = FT = τ (FT 0,max − patm Ae) (7b) The Earth is modelled as oblate spheroid based on the A penalty proportional to atmospheric pressure p and WSG-84 model. The gravitational field was modelled using atm nozzle exit area A is introduced to account for the difference 4th order spherical harmonics (accounting for J , J and J e 2 3 4 in nozzle expansion under pressure compared to in a vacuum. terms) for accelerations in the radial g and transverse g r φ The air-breathing cycle was simulated using a higher directions [11]. The angular rotation of the Earth is assumed fidelity tool designed for combined cycle engines [13], [14]. constant at ω = 7.292115 × 10−5 rad/s. E Due to the high computational overhead, a dataset was T The atmospheric conditions – temperature atm, pressure generated and used to fit a simpler analytic model. The model patm, density ρatm and speed of sound – are modelled in (7) was used with a variable equation for the Isp as a through the global International Standard Atmosphere (ISA) function of altitude, Mach and throttle. The net thrust from model as a function of altitude. the two models are show in Figure 1.

C. Aerodynamics ×106 The aerodynamic model of the vehicle predicts the total 4 coefficient of lift cL and drag cD as a function of the angle of attack α and Mach number M(h, v). For the test 2 case presented here, the aerodynamics were first run with higher fidelity simulations using CFD for the continuum 0 30 regime (lower atmosphere) and Direct Simulation Monte 20 100 Carlo based methods for the upper atmosphere [12] to obtain 10 50 0 0 a set of discrete data points. These data sets were used to

fit a set of polynomial-based surrogate models for cLα and ×106 cD0 . The net values for the cL and cD are then determined based on linearised aerodynamic theory for the supersonic 4 regime and modified Newtonian theory for the hypersonic regime, linked together through a bridging function. The drag 2 C coefficient is calculated as the sum of a term and the Thrust (N) D0 0 induced drag of lifting surfaces (cL tan α). The lift L and 30 20 100 drag D forces in the vehicle body reference frame are given 10 50 by the equations, 0 0 Mach Altitude (km) c ρ v2S c ρ v2S L = L atm ref D = D atm ref (6) Fig. 1: Net maximum thrust for air-breathing cycle (top) and 2 2 rocket (bottom). The mass flow rates are 50 kg/s for the air-breathing cycle, and 890 kg/s for the rocket cycle. where Sref is the total aerodynamic reference area of the 2 vehicle, for this test case Sref = 300 m . E. Trajectory Dynamics and Control nc = 5 control nodes per segment, while Phase 2 has n = 4 A 3-DOF variable point mass dynamic model is used and nc = 5. where the spaceplane is a time-varying mass located at the Table I lists the initial and final boundary conditions, and centre-of-gravity of the vehicle. The state vector for the flight the upper and lower bounds for the state and control vari- x = [r, ˙r] ables. The trajectory is designed to be within the equatorial dynamics dyn is the spherical coordinates for the ◦ position r = [r, λ, θ] and the velocity ˙r = [v, γ, χ] where r plane, starting from a nominal position 0 E longitude on is the radial distance, (λ, θ) are the latitude and longitude, v the equator and ascending to a 100 km, circular equatorial is the magnitude of the relative velocity vector directed by orbit. The arrival true anomaly is left free, with the final γ χ altitude hf = 100 km, orbital velocity vf and flight path the flight path angle and the flight heading angle . The ◦ equation of motion is expressed in the Earth-Centred-Earth- angle γf = 0 set as equality constraints. As the trajectory Fixed F rotating reference frame [15]. is in-plane, the control parameter for the bank angle µ is set to 0. FF ¨r = − 2ω × r − ω × (ω × r) (8) m(t) E E E B. User Defined Constant Control Initialisation A trajectory obtained by using a single shooting approach m(t) where the vehicle mass is a sum of the constant dry per phase with user defined constant control laws has been and payload masses, and the mass of the on-board propellant used as first guess for the gradient-based optimisation of the m (t) = R m˙ dt, FF is net force from the lift L, drag D, p t p control laws. For the first phase, α = 5◦ and τ = 1, while the gravitational forces in the radial and transverse directions second phase α = 20◦ and τ = 1. The optimisation process [mgr, mgφ] and propulsion thrust FT converted from the converges to a final fuel mass mp = 189011 kg after 9013 vehicle body reference frame based on the vehicle angle of model evaluations (∼1800 s on a CORE i5 CPU running α µ attack and bank angle . Matlab 2016a).  FT cos α cos µ−D − g sin γ + g cos γ cos χ m r φ C. Evolutionary Based Initialisation FF =  FT sin µ − g sin χ  (9)  m φ  For this test case, AIDEA is set with DE population size FT sin α cos µ+L n = 20 iun = m − gr cos γ − gφ sin γ cos χ pop , number of AIDEA local restarts max 5, δb = 0.1 where ±δb is added to current solution to The thrust is assumed to be aligned to the x-axis of the create the local bubble for local restart, inflationary tolerance vehicle body reference frame. The explicit equations for the tolconv = 0.25, distance for global restart δc = 0.1, dynamic model can be found implemented in [16], or more adaptation threshold CRC = 3, and the adopted DE strategy generally derived in [11]. was DE/best/1/bin (see [4]). The discrete control law is interpolated using piecewise All reported statistics in Table II are computed on the re- cubic Hermite interpolating polynomial. Within the global sults obtained from 10 independent runs of AIDEA (multiple and local optimisation, the trajectory dynamics are integrated th independent runs allows for the evaluation of the robustness using an non-adaptive 4 order Bogacki-Shampine Runge- of the method). It can be seen that for all the runs the method Kutta method. For the refinement, an adaptive Runge-Kutta −9 converges to a feasible solution, and on 40% of the cases the 4/5 integrator is used with a tolerance of 10 . performance is comparable to, or better than, the solution obtained by user defined single shooting initialisation. The IV. RESULTS extra computational costs are offset by the robustness of the The proposed initialisation approach has been applied approach and the saving in required user expertise and trial- to solve the trajectory optimisation problem related to the and-error time. ascent phase of the spaceplane, from transonic conditions Figures 2–4 show the trajectory dynamics, vehicle mass at low altitude to low orbital boundary conditions. The time history and control law for the best solution in Table outcome of the proposed method is compared to the results II. For the dynamics, Figs. 2–4 show the first guess found of the trajectory optimisation process with a single shooting by AIDEA, the locally optimised solution divided by phases initialisation. to show the optimised switching point for the propulsion mode, the refined solution and the target value. The controls A. Test Case in Fig. 5 show the control nodes for the AIDEA solution The test case is for a payload delivery mission to LEO. and the locally optimal solution, as well as the interpolated The objective function is to minimise the fuel consumption, nodes used by the integrator within the local optimisation mp, which is analogous to maximising the payload delivered and the smoothed interpolation (pchip) used in the refinement to orbit assuming a fixed gross take-off mass for the vehicle, integration step. The duration of each segment within each and therefore that the sum (mp + mpayload) is also fixed. phase is also shown, as the time-of-flight for the segments The problem is decomposed into two phases correspond- were optimisation variables. ing to the two propulsion modes: Phase 1 uses an air- As can be seen, looking at the time history of the vehicle breathing cycle, while Phase 2 uses the rocket cycle. Phase mass (Fig. 4) and throttle (Fig. 5b), the optimised solution 1 is configured with n = 2 multi-shooting segments and follows the expected trend of τ = 1 during the ascent, TABLE I: BOUNDARY CONDITIONSAND BOUNDSON STATE AND CONTROL VARIABLES

Bounds per phase Variable Initial conditions Final conditions Phase 1 Phase 2

Altitude, h h0 = 5 km [0.8h0, 30] km [h0, 1.2hf ] km hf = 100 km Latitude, λ 0 deg N [−45, +45] deg N [−45, +45] deg N free Longitude, θ 0 deg E [−180, +180] deg E [−180, +180] deg E free

Relative velocity, v v0 = 400 m/s [0.5v0, 1000] m/s [0.5v0, 2vf ] vf = 7381 m/s path angle, γ 6 deg [−90, +90] deg [−90, +90] deg 0 deg Flight heading angle χ 90 deg [−180, +180] deg [−180, +180] deg free 5 Vehicle mass, m m0 = 2.47 × 10 kg [mdry, mgtow] [mdry, mgtow] J = min(mp) Angle of attack, α N/A [0, +40] deg [0, +60] deg N/A Engine throttle, τ N/A [0.8, 1] [0.4, 1] N/A Time of flight, ∆t N/A [10, 200] s [50, 500]s N/A with the engine cut-off (τ = 0) during the last segment this approach on such a problem, compared to less than creating a coasting arc. This means that the spaceplane also 1.2×105 evaluations of the evolutionary based initialisation. arrives at the target orbit the correct velocity vector and zero acceleration, which was not added as a constraint in order V. CONCLUSIONS to evaluate the optimality of the solutions found. This paper has introduced an evolutionary-based ini- No matching constraints were imposted between segments tialisation using AIDEA followed by a local optimisation on the controls nor derivative limits on the control imposed procedure to identify clusters of locally optimal solutions, dα/dt ˙u1,k = ˙un+1,k−1 (e.g., to limit or to match 0 f ). For applied to the multi-phase ascent trajectory of a hybrid the most part, the controls are smooth with one exception propulsion spaceplane. The solutions found by this method producing an spike in α (Fig. 5a) between the second and were compared against a more conventional case using a first third segments. Due to the close proximity in time to the two guess generated by with a constant control law per phase, and neighbouring points, the effect on the dynamics in negligible. a random initialisation approach. The user defined constant control initialisation approach requires a degree of trial-and- TABLE II: STATISTICS ON RESULTS FROM AIDEAINI- error and a familiarly with the specific problem, meaning TIALISATION a high cost in terms of human time, while the random approach is computationally expensive. Instead, the AIDEA- Objective function, m (kg) No. Func. Eval. Run ID p based method requires less problem-specific inputs of the Min Mean Max (×105) constant control initialisation approach, and is more efficient 1 188320 199070 236120 1.7262 and more robust at finding a potentially globally optimal 2 208370 221810 226500 1.8099 solution as well as highlighting clusters of locally optimal 3 188390 188510 188780 1.5359 trajectories which can be used by the designer to understand 4 206500 229580 241840 0.75733 the sensitivity of the optimisation variables (for example 5 188440 200510 213320 1.2915 here, the propulsion switching point and control law) to the 6 198500 202310 206200 0.81749 performance or mission objectives and constraints, than the 7 208940 216370 224420 1.0861 random initialisation. 8 215780 222490 229300 0.81134 Future work will investigate better formulations of the 9 188310 194370 205700 1.4598 problem handled by AIDEA, and to improve the robustness 10 206500 229090 242080 1.1883 and the convergence properties of the gradient-based method. This approach will also be applied to more complex, longer duration test cases for future space access vehicles. D. Random Initialisation To better understand the potentialities of the proposed REFERENCES method, 20 optimisation runs have been initialised by uni- [1] R. Varvill and A. Bond, “A comparison of propulsion concepts form random sampling within the entire search space. Of the for SSTO reusable launchers,” Journal of the British Interplanetary 20 runs only two processes converged to feasible results, with Society, vol. 56, no. 3/4, pp. 108–117, 2003. [2] E. Minisci and M. Vasile, “Adaptive inflationary differential evolution,” the objective function mp = [205870, 200220] kg. The 20 5 in IEEE Congress on Evolutionary Computation (CEC2014). Beijin, runs had a total computational cost of 6×10 function evalu- China, 2014. ations. Even if the sampling cannot be considered enough for [3] M. Vasile, E. Minisci, and M. Locatelli, “An inflationary differential a correct statistical analysis of the process performance, the evolution algorithm for space trajectory optimization,” IEEE Transac- 5 tions of Evolutionary Computation, vol. 15, no. 2, pp. 267–281, 2011. success rate of the process is ∼ 0.1 and near 3×10 function [4] K. Price, R. Storn, and J. Lampinen, Differential Evolution. A Practical evaluations should be spent to have a feasible solution with Approach to Global Optimization. Springer, 2005. 8 100 Local optimised solution -phase1 90 7 Local optimised solution -phase2 First guess 80 Target value 6 70 5 60

50 4

Altitude (km) 40

Velocity (km/s) 3 30

20 Local optimised solution -phase1 2 Local optimised solution -phase2 10 First guess Target value 1 0 0 200 400 600 800 1000 1200 1400 0 Ground track (km) 0 1 2 3 4 5 6 7 8 Time (min) (a) Function of ground track (a) 100 45 90 Local optimised solution -phase1 40 Local optimised solution -phase2 80 First guess Target value 35 70

60 30

50 25

Altitude (km) 40 20

30 15 20 Local optimised solution -phase1 Flight path angle (deg) Local optimised solution -phase2 10 10 First guess Target value 5 0 0 1 2 3 4 5 6 7 8 Time (min) 0 0 1 2 3 4 5 6 7 8 (b) Function of time Time (min) Fig. 2: Trajectory altitude showing the first guess from (b) AIDEA, and the locally optimised solution for the two Fig. 3: Trajectory velocity and flight path angle showing the phases. first guess from AIDEA, and the locally optimised solution for the two phases.

[5] B. Addis, M. Locatelli, and F. Schoen, “Local optima smoothing for global optimization,” Optimization Methods and Software, vol. 20, pp. jectories for space access vehicles,” in Space transporta- 417–437, 2005. tion solutions and innovations symposium, International Astronautical [6] R. Gamperle, S. Muller, and P. Koumoutsakos, “A parameter study Congress, 2015. for differential evolution,” in WSEAS International Conference on Advances in Intelligent Systems, Fuzzy Systems, Evolutionary Com- putation, 2002, pp. 293–298. [7] K. Fukunaga, Introduction to Statistical Pattern Recognition. Aca- demic Press, 1972. [8] M. Vasile and V. Becerra, Eds., Computational intelligence in aerospace sciences, ser. Progress in Astronautics and Aeronautics. [9] F. Pescetelli, E. Minisci, C. Maddock, I. Taylor, and R. Brown, “Ascent trajectory optimisation for a single-stage-to-orbit vehicle with hybrid propulsion,” in AIAA/3AF International Space Planes and Hypersonic Systems and Technologies Conference, 2012, p. 5828. [10] R. Longstaff and A. Bond, “The Skylon project,” AIAA Journal, 2011. [11] A. Tewari, Atmospheric and space flight dynamics. Springer, 2007. [12] A. O. Ahmad, C. Maddock, T. Scanlon, and R. Brown, “Prediction of the aerodynamic performance of re-usable single stage to orbit vehicles,” Space Access, 2011. [13] A. Mogavero, I. Taylor, and R. E. Brown, “Hybrid propulsion para- metric and modular model: A novel engine analysis tool conceived for design optimization,” in AIAA International Space Planes and Hypersonic Systems and Technologies Conference, 2014. [14] A. Mogavero, “Toward automated design of combined cycle propul- sion,” Ph.D. dissertation, University of Strathclyde, Glasgow, UK, 2016. [15] N. Vinh, Optimal trajectories in atmospheric flight. Elsevier, 2012, vol. 2. [16] F. Toso, C. Maddock, and E. Minisci, “Optimisation of ascent tra- ×105 Final mass: optimised 58570 kg, first guess: 43976 kg 2.5 Local optimised solution First guess

2

1.5

1 Vehicle mass (kg)

0.5

0 0 1 2 3 4 5 6 7 8 Time (min) Fig. 4: Variation of vehicle mass with time for AIDEA- initialised solution.

60

50

Local nodes (eval ode) First guess 40 Local nodes (control) (deg) α

30

20 Angle of attack,

10

0 0 1 2 3 4 5 6 7 8 Time (min) (a) 1

0.9

0.8

0.7 Throttle

0.6 Local nodes (eval ode) First guess Local nodes (control)

0.5

0.4 0 1 2 3 4 5 6 7 8 Time (min) (b) Fig. 5: Optimised control law showing control nodes and segment time-of-flights for the first guess from AIDEA, and locally optimised interpolated solution.