1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19...

85
1 of 85 Mircea-Vlad Radulescu MECH6251 April 19 th 2016 Concordia University April 19 th 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu Professor Hoi Dick Ng McGill University 260267403 Three Degree of Freedom Sounding Rocket Model with Pitch Control Study

Transcript of 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19...

Page 1: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

1 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Concordia University April 19th 2016

MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

Professor Hoi Dick Ng McGill University

260267403

Three Degree of Freedom Sounding Rocket Model with Pitch Control Study

Page 2: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

2 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Contents List of Figures ............................................................................................................................................ 3

List of tables .............................................................................................................................................. 4

Nomenclature ........................................................................................................................................... 5

1 Introduction ............................................................................................................................................... 9

2 Process ..................................................................................................................................................... 10

3 Two Degree of Freedom Equations of Motion and Trajectory ................................................................ 11

4 Pitch Attitude Control with Thrust Vectoring .......................................................................................... 14

5 Test Case .................................................................................................................................................. 22

Rocket sequence of events ..................................................................................................................... 26

6 Body ......................................................................................................................................................... 27

Rocket Engine Model .............................................................................................................................. 27

Rocket Structure ..................................................................................................................................... 29

Recovery System ..................................................................................................................................... 33

7 Environment ............................................................................................................................................. 34

Earth Model ............................................................................................................................................ 34

Aerodynamics ......................................................................................................................................... 35

Atmosphere ............................................................................................................................................ 36

8 Matlab Simulink Model and Trajectory Results ....................................................................................... 37

9 Pitch Control Models and Results ............................................................................................................ 54

Frozen LQR method closed loop response ............................................................................................. 54

Adaptive Pitch Control System ............................................................................................................... 61

10 Conclusion .............................................................................................................................................. 62

11 References ............................................................................................................................................. 63

12 Appendix ................................................................................................................................................ 66

A Aerobee 150A photos .......................................................................................................................... 66

B Matlab Code ......................................................................................................................................... 70

Page 3: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

3 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

List of Figures

Figure 1 Single Stage Rocket Flight Plan ref.[2] ............................................................................................ 9

Figure 2 Rocket Model Block Diagram ........................................................................................................ 10

Figure 3 Round Earth (1) and Flat Earth (2) Coordinate systems ref.[4] .................................................... 11

Figure 4 Arc-length to flat range justification ............................................................................................. 12

Figure 5 Ballistic Gravity Turn Trajectory Profile ........................................................................................ 13

Figure 6 Basic Rocket Stability, ref.[15] ...................................................................................................... 14

Figure 7 Pitch-Yaw Guidance and Control System for Gravity Turn Rocket, ref.[4] ................................... 15

Figure 8 Rocket pitch guidance and control system in a vertical plane, ref.[7] .......................................... 21

Figure 9 Aerobee 150A Outline Drawing ref.[1] ......................................................................................... 22

Figure 10 Aerobee 150A Stations ref.[1] .................................................................................................... 23

Figure 11 Aerobee 150A Stage 1 Booster ref.[11] ...................................................................................... 24

Figure 12 Aerobee 150A Stage 2 Sustainer ref.[11] .................................................................................... 24

Figure 13 Stage 1 chamber pressure and thrust curve vs time .................................................................. 27

Figure 14 Stage 2 chamber pressure and thrust curve vs time .................................................................. 27

Figure 15 Stage 2 thrust ratio w.r.t. altitude .............................................................................................. 28

Figure 16 Stage 1 & 2 thrust curve .............................................................................................................. 28

Figure 17 Rocket Dimensions Stage1+2 ...................................................................................................... 29

Figure 18 Rocket Dimensions Stage2 .......................................................................................................... 29

Figure 19 Mass and CG Station vs time....................................................................................................... 31

Figure 20 Roll, Pitch, Yaw moment of inertia variation vs time ................................................................. 31

Figure 21 Recovery parachute phases ........................................................................................................ 33

Figure 22 Recovery drag chute sequence non dimensional drag ............................................................... 34

Figure 23 Drag Coefficient .......................................................................................................................... 35

Figure 24 Lift Coefficient ............................................................................................................................. 35

Figure 25 Center of Pressure Location ........................................................................................................ 36

Figure 26 Rocket 2D Simulation .................................................................................................................. 38

Figure 27 Rocket Plant ................................................................................................................................ 39

Figure 28 Gravity Model ............................................................................................................................. 40

Figure 29 Aerodynamic Forces Model ........................................................................................................ 41

Figure 30 Altitude vs range for nominal payload with varying launch angles ............................................ 42

Figure 31 Altitude vs time for min, max, and nominal payload mass ......................................................... 42

Figure 32 Acceleration (magnitude) vs time ............................................................................................... 43

Figure 33 Altitude, Acceleration, Velocity vs time ...................................................................................... 44

Figure 34 Thrust, Drag, Radial, Tangential Forces vs time .......................................................................... 45

Figure 35 Mass, Impulse, CG station vs time .............................................................................................. 46

Figure 36 Roll Moment of Inertia, Pitch/Yaw Moment of Inertia, Cp station vs time ................................ 47

Figure 37 Altitude vs Range, Theta vs time, Rocket Cross-Section CG + Cp locations vs time ................... 48

Figure 38 Zα, Mα, Mq vs time ..................................................................................................................... 49

Figure 39 Rocket Trajectory, Orientation with time-stamps ...................................................................... 50

Page 4: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

4 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 40 Gravity, Sound Speed, Air Density vs time .................................................................................. 51

Figure 41 Temperature, Ambient Pressure, Mach Number vs time ........................................................... 52

Figure 42 Dynamic Pressure vs time ........................................................................................................... 53

Figure 43 Root Locus plot of frozen LQR state space method at Max dynamic pressure design point ..... 57

Figure 44 Bode Gain and Phase Margin Plot of frozen LQR method .......................................................... 58

Figure 45 Frozen LQR method unit step response...................................................................................... 58

Figure 46 Frozen LQR method unit step response with increasing gains ................................................... 59

Figure 47 Closed Loop Initial Response with gimbal servo of Frozen LQR pitch control at Max Q design

point ............................................................................................................................................................ 60

Figure 48 State feedback and Output feedback gains during sustainer phase of flight ............................. 61

Figure 49 Aerobee 150A complete second stage with conical nose .......................................................... 66

Figure 50 Aerobee 150A second stage calibration ..................................................................................... 67

Figure 51 Typical Aerobee Launch from Tower .......................................................................................... 68

Figure 52 Preparation of animals + flight + recovery in the Aerobee at Holloman AFB, 1952 ................... 69

List of tables

Table 1 Rocket Specifications: Ref. [1] ........................................................................................................ 25

Table 2 Mass distribution, ref.[1] ................................................................................................................ 30

Table 3 Inertia Distribution, ref.[1] ............................................................................................................. 32

Table 4 Recovery design point .................................................................................................................... 33

Table 5 Units and conversions .................................................................................................................... 65

Page 5: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

5 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Nomenclature

CG Center of Gravity of vehicle (relates global and local coordinate system by Euler Angles)

CP Center of Pressure (w.r.t. local coordinate system)

XG Global X coordinate system (down range in vertical plane)

YG Global Y coordinate system (side range normal to vertical plane)

ZG Global Z coordinate system (altitude)

Xf Local vehicle longitudinal coordinate system (at CG)

Yf Local vehicle lateral coordinate system (at CG)

Zf Local vehicle vertical coordinate system (at CG)

δ Declination angle (round earth)

Ψ Declination angle (flat earth)

Θ Pitch angle

α Angle of attack

β Side slip angle

Φ velocity vector angle w.r.t. horizon

μ nozzle gimbal angle

I Longitudinal axis

iδ Local declination coordinate system (round earth)

ir Local radial coordinate system (round earth)

ix Local horizon coordinate (flat earth)

iz Local vertical coordinate (flat earth)

u1 Forward acceleration vector

u2 Formal acceleration vector

Ro Earth radius

R,r Distance from global to local coordinate system (flat earth)

H Altitude from surface

D Drag force vector

L Lift force vector

T Thrust force vector

g Gravitational acceleration

m Mass of vehicle

ξ Distance from center of gravity to nozzle gimbal

Declination rate

Velocity vector

Radius rate

,Qd pitch rate

b,d Characteristic length (rocket diameter)

S Characteristic surface (rocket cross-sectional diameter)

CL Lift coefficient

CD Drag coefficient

Page 6: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

6 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

M Mach number

Re Reynolds number

Pδ Arc length of declination

ax Forward Acceleration

az Normal Acceleration

Laplace transform

s Laplace variable

A(s) Acceleration in Laplace domain

V(s) Velocity in Laplace domain

S(s) Position in Laplace domain

Recovery parachute drag force

Recovery parachute drag coefficient

Thrust axis of rotation gimbal

Thrust force balance for pitch rotation dynamic

Thrust axis of rotation gimbal balance for pitch rotation dynamic

Pitch and Yaw torque

Total vehicle length

Gimbal pitch angle

Gimbal yaw angle

X X force about Xf

Y Y Force about Yf

Z Z force about Zf

Φ Roll Euler angle

ϴ Pitch Euler angle

Ψ Yaw Euler angle

P Roll angular velocity

Q Pitch angular velocity

R Yaw angular velocity

U Velocity about Xf

V Velocity about Yf

W Velocity about Zf

Acceleration about Xf

Acceleration about Yf

Acceleration about Zf

Roll Euler angle rate

Pitch Euler angle rate

Yaw Euler angle rate

L Roll moment

M Pitch moment

N Yaw moment

Moment of inertia about Xf

Page 7: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

7 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Moment of inertia about Yf

Moment of inertia about Zf

Roll angular acceleration

Pitch angular acceleration

Yaw angular acceleration

, , ,

, , , , ,

, , , , ,

, , , , ,

, , , ,

, , , , ,

Torque about Xf

Angle of attack rate

Side slip angle rate

Non-dimensional Vertical stability derivative w.r.t. angle of attack

Non-dimensional Pitch Moment stability derivative w.r.t. angle of attack

Non-dimensional Pitch Moment stability derivative w.r.t. pitch rate

XCP Center of pressure location from nose datum about Xf

To Tail center of pressure location from nose datum about Xf

Desired pitch rate

Desired pitch rate delta

Desired gimbal angle profile

Gimbal angle delta

±δμ ° Gimbal angle exceedance

±δϴ ° Pitch deviation

A

B

( ), Q, R, N Quadratic cost function and parameters

K State feedback gain

S, N, Q, R Ricatti equation parameters

LQR Linear Quadratice Regulator

Accelerometer sensor location about Xf

Nominal accelerometer output

( ) Error in gimbal servo vector

( ) Total error vector

Linearized equations of motion terms with stability derivatives

State space model parameters

Page 8: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

8 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

( ) State feedback gain for pitch rate

( ) State feedback gain for normal acceleration

( ) Output feedback gain for pitch rate

( ) Output feedback gain for normal acceleration

Settling time

ζ Damping

w frequency

Page 9: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

9 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

1 Introduction This project consists of the modeling of a rocket trajectory in 2 Dimensions and methods of pitch control

to trail said trajectory. The simulation follows the rocket from motor ignition, with initial launch angle, to

its peak apogee altitude and back down to earth with recovery chute. The model is time driven in

Simulink with inputs from a Matlab script. The rocket input parameters, such as Thrust, Mass, Center of

Gravity, Drag etc. are provided as vectors w.r.t. time or Mach number respectively. This means that a

multi-stage rocket can be built by concatenating stage segments together in one vector input and can

still be run on the Simulink rocket model. A comparison with a real sounding rocket, Aerojet Aerobee

150A, is made and the simulation agrees with NASA data, ref[1]. The main limitation, currently, is that it

is a sounding rocket model, with flat earth assumption; therefore the rocket will fall back down to earth

regardless of apogee velocity. In later upgrades, a round earth model will be built with orbit insertion

check.

There are two coordinate systems, the earth fixed and body fixed coordinate systems. In the body fixed

coordinate system, the rocket structure is symmetric along the XfZf plane and YfZf plane. The global

coordinate system XG is the range direction and ZG is the vertical direction from the launch site, δ is the

declination. The local coordinate system for pitch attitude is located at the center of mass of the rocket,

which changes over the burning time, Xf is longitudinal, Zf is Vertical downwards, and Θ is the Euler angle

between Xf and XG, which is pitch if angle of attack, α, is zero.

Figure 1 Single Stage Rocket Flight Plan ref.[2]

δ ZG

XG

Page 10: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

10 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

2 Process The Simulink model uses ordinary differential equation of order 5 (ode5) method for time stepping and

simulates the rocket body as it moves through the environment along its trajectory in 2 dimensions. The

program is built using a combination of .m and .mdl files. The diagram in Figure 2 illustrates how the

model is organized. Body, Environment, and Graphical Outputs are based on Matlab, and Equations of

Motion, Trajectory Integration, and Pitch Control are based in Simulink, ref.[3].

Figure 2 Rocket Model Block Diagram

Page 11: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

11 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

3 Two Degree of Freedom Equations of Motion and Trajectory

The rocket is assumed to follow a flight in a vertical plane. More specifically, this is the translational

motion of the vehicle center of mass in a vertical plane. The rocket trajectory uses a gravity turn

maneuver, also called zero-lift, which means that the angle Θ is solely driven by the downward pull of

gravity. This is a slow pull, designed to reduce as much as possible any angle of attack, α, the rocket

body might have in its atmospheric ascent. The rocket is a long slender structure, which is stiff and

strong in its longitudinal axis, but pretty frail in its lateral and vertical axes. The attitude control system is

designed to follow the trajectory and limit as much as possible any transverse perturbations, so as to not

damage the vehicle and also not deviate from its path.

Figure 3 Round Earth (1) and Flat Earth (2) Coordinate systems ref.[4]

Starting from a round earth model ref.[4], (Ψ=δ from round to flat)

Declination rate

Radius rate

Forward Acceleration

Normal Acceleration

(

)

Page 12: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

12 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Acceleration inputs u1 and u2 are determined by the sum of acting forces which are lift, L, drag, D, thrust

T, thrust deflection angle, μ, and instantaneous mass, m(t).

Lift and drag depend on

( )

( )

In this model, Lift and Drag are simply assumed to depend on Mach number and angle of attack. The

provided data from the NASA report, ref.[1], provides measured CL, CD, and Center of Pressure Cp graphs

which the model uses.

In order to compare with the test case, the round earth equations are converted to flat earth model by

assuming that the earth’s radius is much larger than the achievable altitude or range of the rocket. This

can be proven by taking the largest design range, with launch angle of 70°, as per ref.[1] of 400km and

comparing it to an earth arc length of the same declination travel.

Figure 4 Arc-length to flat range justification

Assuming flat earth, the acceleration components become,

Forward Acceleration

Normal Acceleration

Velocity and position are integrated in the Simulink Laplace domain.

( ( ) ) ( )

( )

( ( ) ) ( )

( )

Assuming the pitch control limits the angle of attack to near zero, α = 0. Angle Θ equals angle Φ, leading

to the general equation of a gravity turn in a flat earth model.

Page 13: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

13 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

( )

The trajectory curve resembles that of a parabola, ref.[5].

Figure 5 Ballistic Gravity Turn Trajectory Profile

The initial launch angle gives way to gravity and the ϴ equation. Once the thrust is stopped, the pull of

gravity gently brings the rocket back to earth, rendering the payload momentarily floating in space.

During re-entry, the rocket begins to react to atmospheric loads once more. The parachute deploys in

two stages. First a drogue chute deploys to orient the payload and slow it at high airspeeds. Second, the

main chute is deployed at a lower airspeed to slow the vehicle to a reasonable descent rate for payload

conservation upon ground impact.

The main chute dynamics along the body forward velocity vector, assuming point mass, is the following:

Parachutes are normal chosen as per their descent rate,

Page 14: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

14 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

4 Pitch Attitude Control with Thrust Vectoring

Figure 6 Basic Rocket Stability, ref.[15]

Rockets are highly dynamic vehicles with rapid time varying parameters such as inertial and

aerodynamic forces. All rockets are unstable in static condition for roll, pitch and yaw due to large

changes in lift, drag, and center of gravity (CG) and center of pressure (CP) shifts. Once Roll is stabilized,

all three rotation angles and their controllers can be decoupled. The yaw dynamics are similar to pitch

except for gravitational effects. Ballistic rockets employ small fins for their short promenade in the

atmosphere and gimbals/thrusters for the rest of their mission. Note that the stability of such vehicles

varies greatly from t=0 at ground, time at max dynamic pressure, and space. No atmosphere means

negligible damping and greater chance of instability, ref.[4].

As was mentioned earlier, it is necessary for a rocket to maintain its velocity vector as close to its

longitudinal axis as possible in order to limit transverse loads. Perturbations in the angle of attack or side

slip together with a not-so robust control system can quickly escalate to complete vehicle loss in a

matter of seconds. Rockets need guidance to follow a trajectory, for ballistic vehicles that is usually a

gravity turn, ref.[4][7][8]. In order to follow the path and correct for any disturbances and instability,

rockets need active stability and control with use of a gimbal, gyro stabilized platform known as an

inertial measurement unit (IMU). The IMU is usually fitted in the instrument compartment, near the

payload section, and consists of rate gyros and accelerometers. The IMU tells the guidance and control

system the attitude of the vehicle to which to control gimbals on the engine side for thrust vectoring

corrective maneuvers.

To change the pitch attitude, a moment is created by vectoring the engine thrust with gimbals, the

moment arm being CG to nozzle distance ξ. It is usually preferable to have equal and opposite

transverse forces in order to form a pure couple for change of attitude, by use of reaction jets or two

gimbaled engines. This is not always possible and a translation occurs which must be accounted for in

the control system, ref.[4].

Page 15: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

15 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 7 Pitch-Yaw Guidance and Control System for Gravity Turn Rocket, ref.[4]

Assuming small gimbal angle sin(μ) = μ, pitch/yaw control torque can be written as,

[ ( ) ] [ ( ) ]

Moment balance

( ) ( )

In the case when forces are not balanced, Tb=0, transverse force becomes

( )

And the pitch/yaw torque becomes

( )

The deflection angles can be defined as

For the Vertical plane control with pure pitching, δ=π/2. Note that without force balance, control torque

is dependent on the location of CG, ξ.

The translational kinetics of the rocket plant can be written as:

( )

( )

( )

Euler angles {Ψ,ϴ,Φ} represent the orientation of the body frame.

Angular velocity vector is:

Page 16: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

16 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Rotational kinematics equations are represented as:

[

]

[

] [ ]

Assuming that rocket is symmetric about i, Jyy=Jzz and Jxy=Jxz=Jyz=0. Rotational kinetics can be written

as:

( )

( )

For steady pitching motion, the forces and moments at equilibrium can be written as:

For a linearized dynamic model such as the steady pitching motion, it can be assumed that aerodynamic

force and moment perturbations are linearly dependent on flow variables (u, V, W, p, q, R) and control

inputs (μ1, μ2, τx). The linearized equations of motion in terms of small perturbation variables

(u,v,w,Φ,Θ,Ψ,p,q,R, , , ) can be expressed as:

Angle of attack,

Side slip angle,

Assuming small side forces, unsteady aerodynamic stability derivatives .

Similarly for angular rate force derivatives .

Small fins cause negligible roll/yaw coupling and roll/sideslip .

Pitch/yaw symmetry leads to , , .

Change in forward force caused by small thrust deflection is negligible .

It can be seen that longitudinal forces and moments are uncoupled from lateral forces and moments. A

6DOF control system can be built with decoupled controls for roll, pitch, and yaw respectively.

Page 17: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

17 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Note that the pitch and roll inertia of the rocket react one order of magnitude slower than the inertia in

roll.

Motion about pitch equilibrium for longitudinal dynamics becomes,

( )

( )

Assuming angular disturbance only and negligible , the pitch dynamics for becomes

[

]

[

]

[

]

[

]

Stability derivatives can be calculated from their non-dimensional form,

( )

( )

Where the non-dimensional derivatives can be approximated as, ref.[9],

(

)

is tail station, d is characteristic length which is typically rocket diameter.

Nominal trajectory for a mission is calculated before launch as per payload orbital requirements. The

rocket becomes autonomous with the help of its onboard computer moments prior to ignition to run a

multitude of diagnostic checks and runs for flight. The short and highly energetic ascent trip has so many

varying flight parameters that a normal human being would not be able to aptly control it. The onboard

computer, with redundant systems, is able to control the vehicle more efficiently. If something out of

the ordinary does occur, the reaction time is so small that any amount of reasoned action is not

possible. Every conceivable alternative scenario is pre-planned in advanced and the operators simply

follow standard protocols.

Page 18: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

18 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

A pitch control system follows a nominal pitch rate command known as a pitch program. In the case of

the model in this paper, the pitch follows ϴ. Therefore the pitch rate is the derivative of ϴ.

( )

( ) ( )

A simple numerical differentiation algorithm of the first order is used to estimate pitch rate.

Nominal gimbal profile can be calculated by setting and , from pitching moment equation,

ref.[4],

Assuming the round earth model (no earth rotation, no corriolis acceleration) corroborates with the flat

earth model and the numerical pitch rate, can be calculated by the following,

(

)

(

)

( )

The goal of the pitch program is to minimize the difference between desired pitch and angle of attack.

The pitch dynamics plant about the nominal trajectory becomes,

[ ]

[

]

[

]

[

]

This can be written in state space as,

is the corrective gimbal input for pitch attitude control.

The pitch dynamics plant contains the required coefficients as functions of flight time m, U, , , ,

for the nominal trajectory. The vehicle is assumed to contain first order pitch gimbal servos, with a

given time constant.

The control law can be tuned to a design point, such as the maximum dynamic pressure (a.k.a. max Q).

The controller design needs requirements for angle of attack and pitch deviation of ±δϴ °, with

Page 19: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

19 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

saturation, and gimbal angle exceedance of ±δμ °. The closed loop system performance is tested with an

initial response to an initial angle of attack perturbation δα.

Two control methods are built, one using a frozen linear quadratic regulator and another using closed-

form feedback regulator.

Frozen LQR method:

For a continuous time system, the state-feedback law u=-Kx minimizes the quadratic cost function,

ref.[10]

( ) ∫ ( )

Subject to system dynamics

K is derived from S. S is the solution to the Riccati equation.

( ) ( )

( )

Closed loop eigenvalues can be found,

| |

Matlab uses a discrete time state space model which can be run as [K,S,e] = LQR(A,B,Q,R)

Closed-form feedback regulator: (adaptive pitch control system):

For a normal acceleration at the center of mass, , the angle of attack rate is

Accounting for the nominal acceleration of the pitch program,

Normal acceleration output , sensed by an accelerometer located at a distanced along the

longitudinal axis from the center of gravity can be related to

Thrust deflection control can be expressed as

( ) ( ) ( )

is feedforward gimbal angle

Any small deviation from nominal flight path angle , with a small angle of attack α can be

corrected by a linear feedback control.

( ) ( ) ( )

Error vector

( ) ( )

Page 20: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

20 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Tends to zero in the steady-state with a state feedback gain matrix given by

( ) [ ( ) ( )]

Pitch controller is a linear regulator for driving the state error vector ( ) to zero for a given pitch

rate reference, ( ), and a feedforward control input ( ) supplied by the guidance system

(trajectory model), ref[7].

For a closed form solution, the pitch dynamics has the following state space form:

Where

( )

( )

(

)

(

)

(

) (

(

))

As stated earlier, coefficients m, U, , , , , , vary over time. The pitch plant is regarded as

unconditionally controllable, even when stability derivatives go to zero in lack of atmosphere. The linear

feedback regulator can be designed by pole placement.

Regulator control law can be written as,

( )

The gain is therefore

( ) [ ( )

( )]

( ) and

( ) can be derived using the closed loop dynamics matrix and characteristic polynomials.

(

)

| | (

) ( ) ( )

Page 21: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

21 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Selection a closed loop damping ratio of

√ , and a settling time of

State feedback gains become,

( ( ) (

))

(

)

(

( ))

The robustness of the system depends on how well it can adapt to the acceleration and angle of attack

variations.

The figure below presents the typical pitch guidance and control system. The outer dashed lines

represent correction of trajectory errors.(_n is desired, _e is error, and _d is difference)

Figure 8 Rocket pitch guidance and control system in a vertical plane, ref.[7]

Page 22: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

22 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

5 Test Case

To make sure this model reflects the real world, a test case was needed to compare outputs, and the

Aerojet Aerobee 150A was chosen due to its available design specifications and performance data. The

US government initiated its sounding rocket program as a result of the high cost and restrictive payload

of the recovered V-2 rockets from WW2. A study by James Van Allen of John Hopkins University Applied

Physics Laboratory initiated the sounding rocket program based on the WAC Corporal rocket. The

Aerojet Corporation was contracted to build it using technology from the Navy Bumblebee missile

project, the rocket was thus named the Aerobee ref.[11].

The Aerobee 150A is a four fin sounding rocket roughly 30 feet tall, and 15 inches in diameter. The

rocket is capable of transporting 100 to 300 pound payloads to altitudes from 180 to 100 miles high

under a gravity turn maneuver with near vertical launch angles. It is a free flight fin stabilized tower

launched vehicle using a solid propellant booster for stage 1 and a liquid propellant sustainer for stage 2.

ref[1][11][12]

Figure 9 Aerobee 150A Outline Drawing ref.[1]

Page 23: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

23 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 10 Aerobee 150A Stations ref.[1]

Page 24: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

24 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 11 Aerobee 150A Stage 1 Booster ref.[11]

Figure 12 Aerobee 150A Stage 2 Sustainer ref.[11]

Page 25: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

25 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Table 1 Rocket Specifications: Ref. [1]

Vehicle Name Aerobee 150A

Designation Four Finned Aerobee H1

Manufacturer Aerojet-General Corporation, Azusa, California

Number of Stages 2

Launch Mass (no payload) 1947.5 lb 883.37 kg

Total Length 367 in 9.32 m

Maximum Diameter 15 in 0.381 m

Aerodynamic Ref. Area 1.228 ft^2 0.114 m^2

Net Payload

Nominal 200 lb 90.71 kg

Minimum 100 lb 45.35 kg

Maximum 300 lb 136.07 kg

Payload Volume (ogive nose only, no extensions) 4.75 ft^3 0.134 m^3

Performance at Nominal

Apogee Altitude (vertical launch) 117 NM 216 km

Max Acceleration 11 'g'

Performance Mass Phases

Launch 1947.5 lb 883.3 kg

Fire 2nd stage 1916.1 lb 869.1 kg

B. O. 1st stage 1638.4 lb 743.1 kg

Drop 1st stage 1300.4 lb 589.8 kg

B. O. 2nd stage 293.1 lb 132.9 kg

Dispersion at 85° launch angle with nominal payload

Pitch flight path angle ±2 °

Yaw flight path angle ±2 °

Velocity ±1 %

stage 1 = solid propulsion system

Ignition time 0 s

Type 2.5 KS - 18000 booster

Grains AK-14-Mod 1

Charge sodium nitrate black powder

Sea Level Thrust 18600 lbf 82736.89 N

Powered Duration 2.5 s

Chamber Pressure 1340 psia 9238978 Pa

Throat area 8.5 in^2 0.005484 m^2

Expansion Ratio 7.9

Mass Flow Rate 104 lb/s 47.17357 kg/s

Surface to Port Ratio 74

Specific Impulse 178 lb.s/lb 178 kg.s/kg

Flame Temperature 2960 F 1626.667 C

stage 2 = liquid propulsion system

Ignition time 0.3 s

Type hypergolic sustainer

Fuel 65% aniline + 35% furfuryl alcohol,

Oxidizer inhibited red fuming nitric acid

Pressurizing Gas Helium-Grade A

Sea Level Thrust 4100 lbf 18237.7 N

Powered duration 51.5 s

Oxidizer to fuel ratio 2.56:1

Thrust Chamber Pressure 324 psia 2233902 Pa

Propellant flow rate 20.71 lb/s 9.39389 kg/s

Nozzle expansion ratio 4.6

Specific Impulse 198 lb.s/lb 198 kg.s/kg

Total impulse at sea level 208690 lbf.s 928299 N.s

Page 26: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

26 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Rocket sequence of events

Payload is mounted on the nose structure. The mission sequence starts with stage 1 motor ignition a

t=0s. After t=0.3s, stage 2 motor ignites, both stages burn together for 2.2s. Note that stage 1 motor has

deflector nose, to deflect stage 2 exhaust. At t=2.5s, stage 1 motor burns out and falls away. Stage 2

motor continues to burn until t=51.5s ref[1].

The rocket model predictions are compared to those of NASA report ref.[1][11][12]. The NASA flight

performance calculations used a similar 2 degree of freedom analysis on a spherical non-rotating earth.

It considered aerodynamic coefficients dependent on Mach number and corrected for ambient pressure

thrust. NASA used a 1959 ARDC atmospheric model ref.[1]. Trajectories were computed for a nominal

payload of 200lbs with 3 launch angles and compared to those of ref.[1][12].

The most popular televised launch of this rocket occurred on May 22 1952, when two Philippine

monkeys, one in seated and the other in prone position, and two mice were enclosed in an Aerobee

nose section and reached an altitude of 36 miles and maximum speed of 2000mph, ref[13][14]. All

animals survived the flight, and the data recorded led to better understanding of free flight and

acceleration loads on the body.

Page 27: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

27 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

6 Body

Rocket Engine Model

To accurately simulate the thrust of both stages, the chamber pressure vs time curve was normalized

with respect to average chamber pressure and multiplied by the average thrust of each stage

respectively.

stage 1 avg pressure 1340 psi 9238978 Pa

avg thrust 18600 lbf 82737 N @ sea level

Figure 13 Stage 1 chamber pressure and thrust curve vs time

stage 2 avg pressure 324 psi 2233902 Pa

avg thrust 4100 lbf 18238 N @ sea level

Figure 14 Stage 2 chamber pressure and thrust curve vs time

0

20000

40000

60000

80000

100000

120000

0

5000

10000

15000

0 0.5 1 1.5 2 2.5 3 3.5

N

kPa

time [s]

Stage 1 chamber pressure and thrust curve vs time

Stage 1 chamber pressure

Stage 1 thrust curve

0

1000

2000

3000

4000

5000

6000

0

500

1000

1500

2000

2500

3000

-10 0 10 20 30 40 50 60

N

kPa

time [s]

Stage 2 chamber pressure and thrust curve vs time

Stage 2 chamber pressure

Stage 2 thrust curve

Page 28: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

28 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

The second stage thrust curve is also compensated for ambient pressure effects.

Figure 15 Stage 2 thrust ratio w.r.t. altitude

Stage 1 and Stage 2 thrust curves in the same graph shows the difference in scale and burn length.

Figure 16 Stage 1 & 2 thrust curve

0.95

1

1.05

1.1

1.15

1.2

0 10000 20000 30000 40000 50000

altitude [m]

Stage 2 thrust ratio w.r.t. altitude

0

20000

40000

60000

80000

100000

120000

-10 0 10 20 30 40 50 60

N

time [s]

Stage 1 & 2 thrust curve

stage 1

stage 2

Page 29: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

29 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Rocket Structure

The rocket mass is distributed amongst payload, structure, and propellant. The center of gravity varies in

the longitudinal axis of the rocket as the propellant is consumed. The datum of the rocket is the tip of

the nose.

Dimensions

Figure 17 Rocket Dimensions Stage1+2

Figure 18 Rocket Dimensions Stage2

0

0.5

1

1.5

2

0 0.5 1 1.5 2 2.5 3 3.5 4 4.5 5 5.5 6 6.5 7 7.5 8 8.5 9 9.5

Late

ral [

m]

Longtitudinal [m]

Rocket Dimensions Stage1+2

0

0.5

1

1.5

0 0.5 1 1.5 2 2.5 3 3.5 4 4.5 5 5.5 6 6.5 7 7.5 8 8.5 9 9.5

Late

ral [

m]

Longtitudinal [m]

Rocket Dimensions Stage2

Page 30: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

30 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Table 2 Mass distribution, ref.[1]

lb kg

Stage 1* Inert Mass (including fins) 338 153.3

Consumed Mass 262 118.8

Total Stage 1 600 272.2

Stage 2 Inert Mass Nose Cone 17 7.7

Tank Assembly 163 73.9

Shrouds 6.6 3.0

Fairings 0.5 0.2

Aft Structure 15.5 7.0

Fins 28 12.7

Regulator Valve 3 1.4

Regulator Manifold 1 0.5

Thrust Chamber Assembly

Chamber 25.5 11.6

Nike Valve 2.9 1.3

Flex Lines 2 0.9

Shutoff Valves

1.7 0.8

Miscellaneous (lugs, etc.)

12.4 5.6

Helium 7 3.2

Unuseable Fuel 7 3.2

Total Inert 293.1 132.9

Consumed Mass Fuel 296.2 134.4

Oxidizer 758.2 343.9

Total Consumed 1054.4 478.3

Total Stage 2 1347.5 611.2

Payload 200 90.7

Total Mass

2147.5 974.1

*Not included in CG

Page 31: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

31 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

The rocket is a time varying system, this includes mass, center of gravity, moment of inertia about

roll/pitch/yaw.

Figure 19 Mass and CG Station vs time

Figure 20 Roll, Pitch, Yaw moment of inertia variation vs time

0

1

2

3

4

5

6

0

100

200

300

400

500

600

700

800

0 10 20 30 40 50 60

C.G

. St

atio

n [

m]

mas

s [k

g]

time [s]

Mass and CG Station vs time

Mass - Nom

Mass - Min

Mass - Max

CG Sta. - Nom

CG Sta. - Min

CG Sta. - Max

0

500

1000

1500

2000

2500

0

5

10

15

20

0 10 20 30 40 50 60

Pit

ch/

Yaw

Mo

me

nt

of

Ine

rtia

[k

g.m

^2]

Ro

ll M

om

en

t o

f In

ert

ia [

kg.m

^2]

time [s]

Roll, Pitch, Yaw moment of inertia variation vs time

Local Roll Moment of Inertia -Nom

Local Roll Moment of Inertia -Min

Local Roll Moment of Inertia -Max

Local Pitch or Yaw Moment ofInertia - Nom

Local Pitch or Yaw Moment ofInertia - Min

Local Pitch or Yaw Moment ofInertia - Max

Page 32: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

32 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Table 3 Inertia Distribution, ref.[1]

Item Mass C.G. from Ref. Sta. 0.0

Local Roll Moment of Inertia

Local Pitch or Yaw Moment of Inertia

kg m kg.m^2 kg.m^2

Stage 1 1

Stage 2 Nose cone 7.71 1.25 0.14 2.21

Payload Extension (Opt.) 6.35 2.10 0.23 0.15

Tanks and Shrouds 77.16 4.53 2.45 108.94

Thrust Chamber 14.56 6.91 0.26 0.99

Aft Shell 7.03 6.74 0.26 0.54

Fins 12.70 7.06 2.54 2.05

Head End Plumbing 1.81 2.39 0.03 0.02

Miscellaneous (lug, etc.) 5.62 4.27 0.20

Helium 3.18 2.74 0.06 0.18

Unused Fuel 3.18 4.32

Total Inert 139.30 4.77

Fuel 134.35 3.73 2.43 17.86

Oxidizer 343.91 5.38 6.21 127.47

Total Propellant 478.27

Total Loaded 617.57 4.89

Payloads

Min 45.36 1.42 0.82 19.29

Nominal 90.72 1.42 1.64 38.57

Max 136.08 1.42 2.46 57.87

Notes:

1. Not included in CG. 2.5 seconds of burn is too short for inertial control.

2. Empty vehicle C.G. from Ref.1

3. Station 0.0 is 9.4 inches aft of the tip of the nose cone. Vehicle length is 367.0 inches,

including an optional 9.4 inch extension. Performance calculations are based on a vehicle

which does not include either the 9.4 inch or 15 inch optional payload extensions. CG and

inertial curves include a nominal payload plus the 9.4 inch extension.

Page 33: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

33 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Recovery System

When the rocket reaches 18 000’, 5486 meters, it deploys a drogue chute to orient the payload. This

lasts about 12 seconds after which the main chute is deployed. The descent rate is 25 ft/s, 7.62 m/s.

Table 4 Recovery design point

Recovery design point (18000’)

mass 231.02 kg

gravity 9.791 m/s^2

density 0.7364 kg/m^3

descent rate 7.62 m/s 25 ft/s

S*Cd 105.80 m^2

The recovery drag chute has five basic steps. The model follows a 12[s] long sequence to switch from

body drag to body+chute drag forces. Due to simulation instability at stated design point deployment,

the simulation is instead deploying parachute at a higher altitude, ref[16].

Figure 21 Recovery parachute phases

Page 34: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

34 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 22 Recovery drag chute sequence non dimensional drag

7 Environment The external forces acting on the rocket are gravity and aerodynamic lift and drag (nose cone, cylinder

and fins). The center of pressure varies according to vehicle velocity and angle of attack. All aerodynamic

coefficients are mapped as a function of Mach number.

Earth Model

Earth is an oblate spheroid, with varying gravity over its surface. The gravity model used treats the Earth

as a perfect sphere with a radially symmetric distribution of mass. The standard acceleration is as per

International Service of Weights and Measures standard acceleration.

(

)

gh is the gravitational acceleration at height h above sea level.

Ro is the Earth's mean radius.

go is the standard gravitational acceleration.

0.01

0.1

1

10

0 2 4 6 8 10 12

Cd

/Cd

_f [

-]

time [s]

Recovery drag chute sequence, non-dimensional

Page 35: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

35 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Aerodynamics

Coefficient of Drag, CD, as a function of Mach number,

Figure 23 Drag Coefficient

Coefficient of Lift, CL, as a function of Mach number, per degree of angle of attack α,

Figure 24 Lift Coefficient

0

0.2

0.4

0.6

0.8

1

1.2

0 1 2 3 4 5 6 7 8 9 10

Cd

MACH NUMBER

Drag Coefficient

Stage 1

Stage 2 - Thrusting

Stage 2 - Coasting

0

0.1

0.2

0.3

0.4

0.5

0.6

0 1 2 3 4 5 6 7 8 9 10

Cl

MACH NUMBER

Lift Coefficient

Stage 1

Stage 2

Page 36: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

36 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Center of Pressure, Cp, station from nose datum as a function of Mach number,

Figure 25 Center of Pressure Location

Atmosphere

The atmospheric model is 1976 Committee on Extension to the Standard Atmosphere (COESA)-extended

U.S. Standard Atmosphere, which is part of the Matlab Aerospace Blockset. Given geopotential altitude,

the model calculates absolute temperature, pressure and density using standard interpolation formulas.

The COESA model extrapolates temperature linearly and pressure/density logarithmically beyond the

range

0 <= altitude <= 84852 meters (geopotential)

For program soundness, density is set to zero at altitudes above this range.

0

1

2

3

4

5

6

7

8

0 1 2 3 4 5 6 7 8 9 10

Stat

ion

[m

]

MACH NUMBER

Center of Pressure Location

Stage 1

Stage 2

Page 37: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

37 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

8 Matlab Simulink Model and Trajectory Results Model assumptions include

No Earth Rotation

No Coriolis Acceleration

Flat Earth

Constant air adiabatic index

Thrust, Mass, Inertia look-up table

Aerodynamic look-up table w.r.t. Mach Number

Gravity turn initiates at t=1.75 seconds

Fx = max = Tcos(theta) - Dcos(theta)

Fy = may = Tsin(theta) - Dsin(theta) - mg

Run time up to 750 seconds or when rocket reaches -0.1 meter altitude (hits the ground)

Nose accelerometer located 2.2[m] from nose datum

Gimbal servo located at butt-end of rocket from nose datum 7.5[m]

Control feedback operates from t = 5 [s] up to t = 50 [s]

Matlab initial conditions

%Initial Conditions Initial_Altitude = 5; %Rocket Initial Altitude, [m] Earth_Radius = 6378137; %Equatorial Radius, [m] Gravity = 9.80665; %Gravitatinal Acceleration, [m/s.s] Air_Density = 1.2250; %Air Density at 15C ISO standard sea level, [kg/m^3] R = 8.3145; %molar_gas_contant, [kJ/kg.K] M_air = 0.0289645; %air_molar_mass, kg/mol gamma = 1.4; %adiabatic_index S_CD_chute = 105.8; %parachute characteristic area drag, [m^2] launch_angle = 88; % degrees from horizontal

For Simulink diagram please see next page.

Page 38: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

38 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 26 Rocket 2D Simulation

Page 39: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

39 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 27 Rocket Plant

Page 40: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

40 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 28 Gravity Model

Page 41: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

41 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 29 Aerodynamic Forces Model

Page 42: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

42 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Results

Altitude and Range Results w.r.t. Nominal Payload, Varying Launch Angles

NASA data are points, model values are lines.

Figure 30 Altitude vs range for nominal payload with varying launch angles

Altitude Results w.r.t. Test Case Min, Max, Nominal Payloads

NASA data are points, model values are lines.

Figure 31 Altitude vs time for min, max, and nominal payload mass

Notice the trailing time-altitude at the end of the trajectory, this is the recovery parachute phase.

-50

0

50

100

150

200

250

0 50 100 150 200 250 300 350 400

alti

tud

e (

km)

range(km)

Altitude vs range for nominal payload with varying launch angles

70

80

88

88_calc

80_calc

70_calc

-100

0

100

200

300

400

0 100 200 300 400 500 600 700 800 900

alti

tud

e (

km)

time (s)

Altitude vs time for min, max, and nominal payload mass

136 kg

91 kg

45 kg

136_calc

91_calc

45_calc

Page 43: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

43 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Acceleration Results w.r.t. Test Case Min, Max, Nominal Payloads

NASA data are points, model values are lines.

Figure 32 Acceleration (magnitude) vs time

Notice that there the NASA data points do not exactly align with model acceleration values. The model

profile is more jagged due to the thrust profile normalized to the chamber pressure profile. The error

seems acceptable, as the position, double integral in time, matches quite well the NASA data.

-2

0

2

4

6

8

10

12

14

16

18

0 10 20 30 40 50 60

Acc

ele

rati

on

(g)

time (s)

Acceleration (magnitude) vs time

45 kg

91 kg

136 kg

45_calc

91_calc

136_calc

Page 44: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

44 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Rocket model parameter variation during flight time for nominal payload

Figure 33 Altitude, Acceleration, Velocity vs time

Page 45: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

45 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 34 Thrust, Drag, Radial, Tangential Forces vs time

Page 46: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

46 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 35 Mass, Impulse, CG station vs time

Page 47: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

47 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 36 Roll Moment of Inertia, Pitch/Yaw Moment of Inertia, Cp station vs time

Page 48: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

48 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 37 Altitude vs Range, Theta vs time, Rocket Cross-Section CG + Cp locations vs time

Page 49: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

49 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 38 Zα, Mα, Mq vs time

Page 50: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

50 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 39 Rocket Trajectory, Orientation with time-stamps

Page 51: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

51 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 40 Gravity, Sound Speed, Air Density vs time

Page 52: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

52 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 41 Temperature, Ambient Pressure, Mach Number vs time

Page 53: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

53 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 42 Dynamic Pressure vs time

Page 54: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

54 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

9 Pitch Control Models and Results

Frozen LQR method closed loop response

Inputs:

a11 = Z_alpha(q_bar_max_launch_i)/Mass(q_bar_max_launch_i)/Ue(q_bar_max_launch_i); a12 = -grav_h(q_bar_max_launch_i)*sin(theta(q_bar_max_launch_i))/Ue(q_bar_max_launch_i); a13 = 1; a21 = 0; a22 = 0; a23 = 1; a31 = M_alpha(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_launch_i); a32 = 0; a33 = M_q(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_launch_i); %pitch dynamics A = [a11 a12 a13; a21 a22 a23; a31 a32 a33]; damp(A) b1 = Thrust(q_bar_max_launch_i)/Mass(q_bar_max_launch_i)/Ue(q_bar_max_launch_i); b2 = 0; b3 = Thrust(q_bar_max_launch_i)*epsilon(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_launch_i); B = [b1 b2 b3]'; C = [0 1 0]; D = 0; %Regulator design by LQR [k,S,E] = lqr(A,B,[0.01 0 0; 0 0.1 0;0 0 0.1],1) %Observer (kalman filter) design by LQR Lp = lqr(A',C',eye(3),1);L = Lp' %Augmented plant with gimbal servo Abar = [A B; zeros(1,3) -time(q_bar_max_launch_i)] Bbar = [0 0 0 time(q_bar_max_launch_i)]' Cbar = [C 0] %Servo augmented closed-loop system Ac = [Abar -Bbar*k;L*Cbar A-L*C-B*k] Bc = [Bbar*k; B*k] %Closed loop system with pitch angle output sys = ss(Ac, Bc(:,2), [0 1 0 zeros(1,4)],0) %Closed loop initial response [y,t,x] = initial(sys,[0.1 0 0 0 0 0 0]');

Max Dynamic Pressure Design Point:

q_b_a_r 81764 N/m^2,

time 22 s,

altitude 8446 m,

airspeed 573 m/s,

Mach 1.87,

mass 520.38 kg,

Z\alpha -3195.31 N/rad,

M\alpha 10028.87 N.m/rad,

M_q -42.92 N.m.s/rad,

epsilon 3.01 m,

b 0.38 m,

S 0.11 m^2,

theta 86.35 °,

Thrust 21584.51 N,

Jyy 1849.74 kgm^2

Page 55: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

55 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%pitch dynamics properties Eigenvalue Damping Frequency

-2.35e+00 1.00e+00 2.35e+00

2.30e+00 -1.00e+00 2.30e+00

1.70e-02 -1.00e+00 1.70e-02

(Frequencies expressed in rad/TimeUnit)

%Regulator design by LQR k =

0.1644 0.3551 0.3592

S =

0.7692 -0.7654 0.0031

-0.7654 0.8932 0.0117

0.0031 0.0117 0.0102

E =

-11.5458

-0.0208

-1.1141

%Observer (kalman filter) design by LQR L =

7.2289

5.8649

16.6984

%Augmented plant with gimbal servo Abar =

-0.0107 -0.0170 1.0000 0.0724

0 0 1.0000 0

5.4218 0 -0.0232 35.1715

0 0 0 -21.7500

Bbar =

0

0

0

21.7500

Cbar =

0 1 0 0

%Servo augmented closed-loop system Ac =

-0.0107 -0.0170 1.0000 0.0724 0 0 0

0 0 1.0000 0 0 0 0

5.4218 0 -0.0232 35.1715 0 0 0

0 0 0 -21.7500 -3.5758 -7.7229 -7.8134

0 7.2289 0 0 -0.0226 -7.2716 0.9740

0 5.8649 0 0 0 -5.8649 1.0000

0 16.6984 0 0 -0.3606 -29.1870 -12.6581

Bc =

0 0 0

0 0 0

0 0 0

3.5758 7.7229 7.8134

0.0119 0.0257 0.0260

0 0 0

5.7824 12.4886 12.6349

Page 56: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

56 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%Closed loop system with pitch angle output sys =

a =

x1 x2 x3 x4 x5 x6 x7

x1 -0.01072 -0.01704 1 0.0724 0 0 0

x2 0 0 1 0 0 0 0

x3 5.422 0 -0.0232 35.17 0 0 0

x4 0 0 0 -21.75 -3.576 -7.723 -7.813

x5 0 7.229 0 0 -0.0226 -7.272 0.974

x6 0 5.865 0 0 0 -5.865 1

x7 0 16.7 0 0 -0.3606 -29.19 -12.66

b =

u1

x1 0

x2 0

x3 0

x4 7.723

x5 0.02571

x6 0

x7 12.49

c =

x1 x2 x3 x4 x5 x6 x7

y1 0 1 0 0 0 0 0

d =

u1

y1 0

Continuous-time state-space model.

Stability can be assessed by looking at the poles of the closed loop transfer function, ref[17].

Test = feedback(sys,1); pole(Test)

-21.1548 + 0.0000i

-13.0952 + 0.0000i

-1.3754 + 2.2108i

-1.3754 - 2.2108i

-2.3496 + 0.0000i

-0.9579 + 0.0000i

-0.0213 + 0.0000i

The feedback loop for k =1 is stable since all poles have negative real parts. This is a binary assessment

of stability.

Page 57: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

57 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

The Continuous-time transfer function.

271.6 s^4 + 1608 s^3 + 3152 s^2 + 2151 s + 45.57

-----------------------------------------------------------------------------

s^7 + 40.33 s^6 + 503.5 s^5 + 2067 s^4 + 4459 s^3 + 5425 s^2 + 2256 s + 44.55

To determine robustness, a root locus plot is needed to find a range of k values which are stable.

Figure 43 Root Locus plot of frozen LQR state space method at Max dynamic pressure design point

When locus intersects the y axis feedback loop is stable with positive damping for k = 34.8. This range

shows that with k=1, the loop gain can increase up to 3480% before you start to lose stability.

Model errors are most damaging near the gain crossover frequency (frequency where open-loop gain is

0dB). It is necessary to know how much phase variation can be tolerated at this frequency.

The gain margin measures what relative gain variation is needed at the gain crossover frequency to lose

stability. The phase margin measures how much phase variation is needed at the gain crossover

frequency to lose stability. These gain and phase margin give an estimate of the "safety margin" for

closed-loop stability. The smaller the stability margins, the more unstable the system becomes.

Page 58: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

58 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

A Bode plot can determine gain and phase margins.

Figure 44 Bode Gain and Phase Margin Plot of frozen LQR method

The gain margin is 31.2 dB and the phase margin is 177 degrees. The corresponding closed-loop step

response exhibits about 10% overshoot and some oscillations.

Figure 45 Frozen LQR method unit step response

Page 59: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

59 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Further study on varying the gain shows an increase in overshoot and less damping. Note that when the

gain approaches gain margin of 31dB, the system shows the signs of instability.

Figure 46 Frozen LQR method unit step response with increasing gains

Page 60: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

60 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Initial response of the closed loop system with gimbal servo to a 0.1 [rad] (5.7°) angle of attack

perturbation is plotted. Notice that the settling time of 10[s], as compared to the burn time of the

rocket of 51.5 [s], means that not many corrective maneuvers could be done with a gimbal servo time

constant of 0.02s.

Figure 47 Closed Loop Initial Response with gimbal servo of Frozen LQR pitch control at Max Q design point

Frozen LQR method does not perform well outside the design point. Gains for all the mission time steps

must therefore be calculated if LQR is used for the entire powered flight regime.

Page 61: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

61 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Adaptive Pitch Control System

An adaptive pitch control system can be built by calculation of feedback regulator gains in closed form.

The state feedback gains, [ ], derived using the characteristic polynomial can be calculated for the

sustainer flight regime. Settling times of 5, 10, and 20 [s] are used. Once known, the output feedback

gains, [ ( )

( )], can be determined using equation ( ) .

Figure 48 State feedback and Output feedback gains during sustainer phase of flight

The output feedback gains seem stable throughout the burn time except for t = 10[s]. An event must be

occurring between 5 and 10 [s] of flight time which leads to instability for ts=10[s], it could be the rapid

change in center of pressure station coupled with center of gravity station change. During sustainer

phase, the rocket is still below 50 [km], which helps reduce gain deviation. Notice near the 50 [s] that

the output gains start to diverge, due to lower air density. Once the air thins out completely, divergence

will become more pronounced.

Page 62: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

62 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

10 Conclusion

The goal of the simulation is to understand the flight parameters of a rocket with a given thrust curve,

aerodynamic properties, inertia, and pitch stability properties. The program bodes well with NASA data,

ref.[1], with very good matches on altitude, range, time, and agrees well with acceleration.

Results of the test case show that the flight regime of the rocket is very fast paced during its powered

ascent, with a reduction of mass of 78% in 51.5[s], an observed acceleration of about 13g, and airspeeds

of up to 1700 m/s. The booster gives a powerful initial kick, and the steady sustainer pushes the rocket

much further. It is interesting to see how the center of pressure moves backward as airspeed increases.

Drag follows a similar tendency. The rocket experiences “weightlessness” for about 400[s].

The report outlines the derivation of attitude dynamics and the de-coupling of Roll, Pitch, and Yaw

control schemes. The pitch control system, a.k.a. pitch program, needs to compensate for variance of

center of pressure and center of gravity which are reflected in the aerodynamic stability derivatives.

Linear Quadratic Regulator and Adaptive pole placement showcase the stability range of the rocket and

the inherent difficulty to achieve acceptable levels of control. Selecting settling times for gains

necessitates a study of the entire flight regime. The vehicle requires a databank of feedback gains to

which the inertial measurement unit together with the control algorithm refers to in-flight for initiation

of corrective maneuvers.

Improvements for future release of this program are,

Round earth model

Determine if orbital velocity is achieved and give orbit parameters.

Rotating Earth

Wind disturbance

Robust 3DOF pitch control with projected corrective path witness to standard wind gusts

6DOF model

Aerodynamic Heating of Rocket Surfaces

Axial, Shear, and Bending Moment loads

Thrusting capability

2 Point Boundary Value Problem Goddard Rocket Problem design

2 Point Boundary Value Problem Gravity Turn with modulated forward acceleration design

Page 63: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

63 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

11 References

[1]K. M. Russ, F. W. Randall, "Performance summary for the Aerobee 150A Sound Rocket Vehicle",

report no. AST/EIR-13319, Vought Astronautics, 1961.

[2]"Index of Rocket Slides", Grc.nasa.gov, 2016. [Online]. Available: https://www.grc.nasa.gov/www/k-

12/rocket/shortr.html. [Accessed: 17- Apr- 2016].

[3]Seffat M. Chowdhury, Jean-François P. Pitot de la Beaujardiere, Michael J. Brooks and Lance Roberts,

"An Integrated Six Degree-of-Freedom Trajectory Simulator for Hybrid Sounding Rocket ", AIAA 2011-

1223, 49th AIAA Aerospace Sciences Meeting including the New Horizons Forum and Aerospace

Exposition, 4 - 7 January 2011, Orlando, Florida, 2011.

[4]A. Tewari, Automatic control of atmospheric and space flight vehicles: Design and analysis with

Matlab(r) and Simulink(r). United States: Birkhauser Boston, 2011.

[5]"Copenhagen Suborbitals | Gyldendal - Den Store Danske", Denstoredanske.dk, 2016. [Online].

Available:

http://denstoredanske.dk/It,_teknik_og_naturvidenskab/Astronomi/Rumfart/Copenhagen_Suborbitals.

[Accessed: 17- Apr- 2016].

[6]G. M. Siouris, Missile guidance and control systems. United States: Springer-Verlag New York, 2004.

[7]A. Tewari, Advanced control of aircraft, spacecraft, and rockets. United Kingdom: Wiley-Blackwell (an

imprint of John Wiley & Sons Ltd), 2011.

[8]A. Tewari, Atmospheric and space flight dynamics: Modeling and simulation with MATLAB and

Simulink. United States: Birkhauser Boston, 2006.

[9]J. Blakelock, Automatic control of aircraft and missiles. New York: Wiley, 1991.

[10]"Linear-Quadratic Regulator (LQR) design - MATLAB lqr", Mathworks.com, 2016. [Online]. Available:

http://www.mathworks.com/help/control/ref/lqr.html. [Accessed: 17- Apr- 2016].

[11]J. R. Busse, M. T. Leffler, "A compedium of Aerobee Sounding Rocket Launchings from 1959 through

1963", TR R-226/N66-14910, NASA, Washington, D. C., 1966.

[12]J. R. Busse, E. C. Pressly, "Sounding Rockets", NASA TMX-55123, Goddard Space Flight Center, NASA,

Greenbelt, Maryland, 1965.

[13]"Aerobee Rocket Launches Monkeys & Mice: "ANIMALS IN ROCKET FLIGHT" 1953 USAF", YouTube,

2016. [Online]. Available: https://www.youtube.com/watch?v=PCSPeUPATY8&nohtml5=False.

[Accessed: 17- Apr- 2016].

Page 64: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

64 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

[14]"Animals in Space", History.nasa.gov, 2016. [Online]. Available:

http://history.nasa.gov/printFriendly/animals.html. [Accessed: 17- Apr- 2016].

[15]B. D. Kothmann, "MEAM 247b : Rocket Stability," in upenn.edu, 2015. [Online]. Available:

http://medesign.seas.upenn.edu/uploads/Courses/stability_Kothmann.pdf. Accessed: Apr. 17, 2016.

[16]K. F. Doherr, "Parachute flight dynamics and trajectory simulation", Lecture series "Heinrich

parachute systems short course", University of St. Louis, St. Louis, Missouri,2002.

[17]"Assessing Gain and Phase Margins - MATLAB & Simulink", Mathworks.com, 2016. [Online].

Available: http://www.mathworks.com/help/control/ug/assessing-gain-and-phase-margins.html.

[Accessed: 17- Apr- 2016].

Page 65: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

65 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Table 5 Units and conversions

Unit conversion

lb to kg 0.453592

in to m 0.0254

ft to m 0.3048

in^2 to m^2 6.45E-04

ft^2 to m^2 0.092903

ft^3 to m^3 0.0283168

NM to km 1.852

lbf to N 4.44822

psi to Pa 6894.76

°F to °C (F-32)/1.8

slug ft^2 to kg m^2 1.3558179

molar gas contant 8.3145 kJ/kg.K

air molar mass 0.0289645 kg/mol

temperature 273.15 K

adiabatic index 1.4

speed of sound 331.32154 m/s

Page 66: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

66 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

12 Appendix

A Aerobee 150A photos

Figure 49 Aerobee 150A complete second stage with conical nose

Page 67: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

67 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 50 Aerobee 150A second stage calibration

Page 68: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

68 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 51 Typical Aerobee Launch from Tower

Page 69: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

69 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Figure 52 Preparation of animals + flight + recovery in the Aerobee at Holloman AFB, 1952

Page 70: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

70 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

B Matlab Code % 2D rocket model % Vehicle Name: Aerobee 150A % Designation: Four Finned Aerobee H1 % Manufacturer: Aerojet-General Corporation, Azusa, California % Number of Stages: 2 % Launch Mass: 1947.5 lb (no payload) % Total Length: 367.0 in % Maximum Diameter: 15.0 in % Aerodynamic Ref. Area: 1.228 ft^2 % Net Payload % Nominal: 200.0 lb % Minimum: 100.0 lb % Maximum: 300.0 lb % Payload Volume: 4.75 ft^3 (ogive nose only, no extensions) % Performance at Nominal % Apogee Altitude: 117 NM (vertical launch) % Max Acceleration: 11 'g' % Performance Mass Phases % Launch: 1947.5 lb % Fire 2nd stage: 1916.1 lb % B. O. 1st stage: 1638.4 lb % Drop 1st stage: 1300.4 lb % B. O. 2nd stage: 293.1 lb % Dispersion at 85° launch angle with nominal payload % Pitch flight path angle: ±2 ° % Yaw flight path angle: ±2 ° % Velocity: ±1 % % stage 1 = solid propulsion system % Ignition time: 0 s % Type: 2.5 KS - 18000 booster % Grains: AK-14-Mod 1 % Charge: sodium nitrate black powder % Sea Level Thrust: 18600 lbf % Powered Duration: 2.5 s % Chamber Pressure: 1340 psia avg % Throat area: 8.5 in^2 % Expansion Ratio: 7.9 % Mass Flow Rate: 104 lb/s % Surface to Port Ratio: 74 % Specific Impulse: 178 lb.s/lb % Flame Temperature: 2960 F % stage 2 = liquid propulsion system % Ignition time: 0.3 s % Type: hypergolic sustainer % Fuel : 65% aniline + 35% furfuryl alcohol, % Oxidizer: inhibited red fuming nitric acid % Pressurizing Gas: Helium-Grade A % Sea Level Thrust: 4100 lbf % Powered duration: 51.5 s % Oxidizer to fuel ratio: 2.56 to 1 % Thrust Chamber Pressure: 324 psia % Propellant flow rate: 20.71 lb/s % Nozzle expansion ratio: 4.6 % Specific Impulse: 198 lb.s/lb % Total impulse at sea level: 208690 lb.s

Page 71: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

71 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%NOTES: % -Performance based on nominal payload of 200 lb % -Thrust stages, mass, CG, Jxx/yy/zz, Cd, Cl, Cp are in vector form % -Thrust_Time vector is driver clc clear all close all %Dimensions Diameter = 0.381; %Rocket Diameter, [m] Length = 9.3218; %Rocket Length, [m]

%Thrust as a function of time thrust_time_1 = [ 0, 0.335027, 0.373808, 0.410489, 0.437779, 0.510458,

0.646354, 1.002316, 1.18475, 1.379931, 1.579187, 1.761423, 1.969029,

2.091711, 2.248451, 2.388046, 2.493743, 2.582401, 2.679498, 2.729914,

2.78015, 2.864427]; thrust_stage_1 = [ 261.0176677, 4106.308019, 13532.93389, 54153.94988,

81408.639, 90826.37924, 95247.01916, 95677.976, 99037.8845, 102918.7176,

104439.2845, 104915.7806, 104599.2273, 101683.6042, 101118.251, 97673.92825,

94238.49127, 89496.85512, 84228.74072, 77924.33063, 68998.63651,

297.6712222];

thrust_time_2 = [ -1.066946, -0.189914, 0.185234, -0.09307, 0.780414,

1.659106, 2.601506, 3.728536, 5.608353, 6.610384, 8.616408, 9.806239,

11.623255, 13.127245, 14.69313, 16.009244, 16.760597, 17.888759, 18.953742,

19.956301, 21.773015, 22.775801, 24.028434, 24.717967, 25.907874, 26.660057,

27.787087, 28.790174, 31.29544, 32.737157, 33.425935, 34.115468, 34.303269,

35.055377, 35.368478, 36.057785, 38.187147, 38.814181, 40.192643, 40.568244,

41.320428, 48.650538, 50.406186, 51.59367]; thrust_stage_2 = [ 1214.763008, 1264.213636, 1750.868758, 19597.97699,

21933.05462, 20912.63729, 19211.45349, 19650.1814, 19457.41767, 19701.50691,

18925.29607, 19266.82181, 19171.26019, 18929.51461, 19174.13116, 18883.57941,

19176.06464, 18885.33715, 18934.96352, 18838.64025, 18937.6001, 18695.38574,

18939.70937, 18697.20208, 18990.0975, 18747.64875, 19186.37665, 18749.64082,

19238.28808, 18753.33205, 18997.12835, 18754.62107, 18852.05757, 18658.2392,

18755.7929, 18659.17664, 19147.47237, 18807.64572, 18711.67398, 18906.54698,

18664.09829, 18670.95342, 17748.6171, 1749.286806];

Thrust_Time = 0:0.1:51.5;length(Thrust_Time) for i = 1:length(Thrust_Time) if Thrust_Time(i) < thrust_time_1(end) Thrust_Newton(i) =

interp1(thrust_time_1,thrust_stage_1,Thrust_Time(i)) +

interp1(thrust_time_2,thrust_stage_2,Thrust_Time(i)); else Thrust_Newton(i) =

interp1(thrust_time_2,thrust_stage_2,Thrust_Time(i))*1.14; end end Total_Impulse = trapz(Thrust_Time,Thrust_Newton); %[N.s] Thrust_Average = Total_Impulse/(Thrust_Time(end)-Thrust_Time(1)); % [N] Total_Burn_Time = Thrust_Time(end); % tb, [s]

Propel_Mass1 = 118.8; %Mass of Propellant stage 1, [kg] Propel_Mass2 = 478.27; %Mass of Propellant stage 2, [kg] Rocket_Inert_Mass1 = 153.3; %Rocket Empty Mass stage 1 only, [kg]

Page 72: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

72 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

Rocket_Inert_Mass2 = 139.30; %Rocket Empty Mass stage 2 only, [kg] Payload_Mass = 90.7*1.0; %payload, [kg]

mass_1_time = [ 0, 2.5]; mass_1_kg = [ Propel_Mass1 + Rocket_Inert_Mass1 + Propel_Mass2 +

Rocket_Inert_Mass2 + Payload_Mass,... Rocket_Inert_Mass1 + Propel_Mass2 + Rocket_Inert_Mass2 + Payload_Mass]; mass_2_time = [ 2.5, 51.5 ]; mass_2_kg = [ Propel_Mass2 + Rocket_Inert_Mass2 + Payload_Mass,... Rocket_Inert_Mass2*1.0 + Payload_Mass];

for i = 1:length(Thrust_Time) if Thrust_Time(i) < mass_1_time(end) Mass_Total(i) = interp1(mass_1_time,mass_1_kg,Thrust_Time(i)); else Mass_Total(i) = interp1(mass_2_time,mass_2_kg,Thrust_Time(i)); end end

thrust_alt_m = [ 0, 1576.268018, 3379.238657, 5260.300884, 7371.615432,

10317.80034, 13420.16874, 17209.0336, 21304.82262, 25783.97048, 31403.96615,

36264.81657, 41125.90352, 45759.10493 ]; thrust_alt_factor = [ 1.0, 1.023815077, 1.04912016, 1.071749163, 1.091406494,

1.111966352, 1.12717405, 1.138820746, 1.146604359, 1.149930927, 1.151486723,

1.152438362, 1.153092557, 1.153743971 ];

cg_time = [ 0, 1.43586, 3.123567, 5.065739, 7.008387, 9.373081, 12.076268,

14.188401, 16.301486, 18.584532, 20.445056, 22.306533, 24.168009, 26.199446,

27.725285, 29.082116, 31.116886, 32.475145, 34.004316, 35.449936, 36.894604,

38.511136, 39.873204, 41.238128, 42.773013, 44.05248, 44.821589, 45.935856,

47.1332, 48.673797, 49.789493, 50.90376, 51.5 ]; cg_station_m = [ 4.444583846, 4.453417763, 4.464460108, 4.471219379,

4.475818861, 4.482638965, 4.487347947, 4.489811925, 4.487956328, 4.481805464,

4.475593741, 4.465062419, 4.454531121, 4.439704532, 4.41832553, 4.396922194,

4.366977017, 4.339094268, 4.302596653, 4.26176727, 4.225257488, 4.175813238,

4.130652089, 4.072532139, 4.010116897, 3.956304381, 3.917537453, 3.846422178,

3.781798456, 3.693465613, 3.615870924, 3.544755649, 3.454214326 ];

for i = 1:length(Thrust_Time) cg_station(i) = interp1(cg_time,cg_station_m,Thrust_Time(i)); end

jxx_time = [ 0, 52.458164 ]; jxx_kgm2 = [ 16.44834949, 7.823865429 ]; jyyzz_time = [ 0, 1.773877, 4.478493, 7.098604, 9.80322, 12.930833,

15.805886, 18.258417, 21.302002, 24.347968, 26.20754, 29.253505, 31.878377,

36.02528, 38.989122, 42.038896, 44.835633, 47.719731, 50.18226, 52.393655 ]; jyyzz_kgm2 = [ 1921.810166, 1922.352359, 1918.595731, 1914.813284,

1911.056656, 1902.846293, 1885.392817, 1867.810247, 1854.991236, 1819.258084,

1815.243268, 1779.510117, 1729.899385, 1671.587735, 1612.914622, 1540.518842,

1463.462778, 1358.935562, 1245.113596, 1108.300033 ];

for i = 1:length(Thrust_Time) jxx(i) = interp1(jxx_time,jxx_kgm2,Thrust_Time(i)); jyyzz(i) = interp1(jyyzz_time,jyyzz_kgm2,Thrust_Time(i));

Page 73: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

73 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

end

cp1_mach = [ 0, 0.160968, 0.393693, 0.589701, 0.76123 ]; cp1_station_m = [ 7.092056174, 7.0903449, 7.119246239, 7.148489843,

7.177961616 ]; cp2_mach = [ 0.024553, 0.23298, 0.441407, 0.674492, 0.895607, 1.032126,

1.168645, 1.243968, 1.380128, 1.515479, 1.760174, 1.906415, 2.125643,

2.308513, 2.503442, 2.71079, 2.954946, 3.21134, 3.443526, 3.736639, 3.993304,

4.237819, 4.494663, 4.800375, 5.228838, 5.510251, 6.024299, 7.015677,

7.994727, 8.986105, 9.977574 ]; cp2_station_m = [ 4.668108368, 4.728306825, 4.788505257, 4.879544495,

5.017301192, 5.342270164, 5.66723911, 5.992778489, 6.255609561, 6.378630397,

6.360814228, 6.250703932, 6.062236771, 5.936249748, 5.779079679, 5.652864488,

5.54184152, 5.430704455, 5.36639897, 5.254919665, 5.190386012, 5.141500918,

5.10803619, 5.058580688, 5.070122194, 5.05196381, 5.047172253, 5.037931428,

5.013270238, 5.004029413, 5.01032305 ];

cl1_mach = [ 0.017739, 0.225854, 0.409595, 0.556737, 0.728627, 0.851619,

0.901339 ]; cl1= [ 0.491016, 0.495786, 0.501796, 0.509053, 0.521193, 0.533363, 0.546802

]; cl2_mach = [ 0, 0.226123, 0.397116, 0.678055, 0.922022, 1.057537, 1.169276,

1.244342, 1.380903, 1.528195, 1.661319, 1.842669, 2.060916, 2.291313,

2.497934, 2.765752, 3.094991, 3.399856, 3.765992, 4.119755, 4.498266,

4.852178, 5.181865, 5.633723, 6.110104, 6.513362, 6.940771, 7.33188, 7.80841,

8.260417, 8.724798, 9.140356, 9.445893, 10.008294 ]; cl2 = [ 0.298761, 0.299865, 0.297312, 0.293466, 0.284745, 0.301805, 0.3299,

0.358018, 0.392221, 0.401927, 0.379804, 0.346631, 0.317109, 0.286356,

0.266637, 0.248106, 0.234435, 0.222003, 0.211983, 0.199521, 0.191942,

0.181929, 0.175605, 0.167981, 0.161567, 0.158871, 0.151263, 0.149799,

0.145833, 0.140659, 0.137925, 0.136446, 0.135035, 0.135915 ];

cd1_mach = [ 0, 0.141386, 0.287971, 0.416175, 0.526164, 0.654535, 0.773715,

0.828894, 0.88404 ]; cd1= [ 0.715058, 0.722303, 0.725872, 0.726777, 0.731211, 0.740308, 0.747573,

0.760399, 0.771388 ]; cd2_mach = [ 0, 0.083356, 0.229907, 0.376392, 0.541259, 0.687877, 0.798403,

0.890682, 0.955857, 0.99366, 1.00369, 1.00469, 1.005535, 1.079599, 1.253589,

1.344224, 1.453039, 1.562089, 1.689487, 1.807661, 1.971522, 2.144673,

2.317859, 2.536965, 2.737958, 2.993929, 3.25, 3.606836, 3.927211, 4.293338,

4.696163, 4.989065, 5.364518, 5.64833, 5.977928, 6.985174, 7.983262,

9.018114, 9.979538 ]; cd2 = [ 0.553313, 0.553233, 0.554963, 0.553017, 0.554734, 0.560141, 0.594985,

0.633519, 0.692293, 0.756602, 0.804387, 0.848517, 0.905486, 0.949548,

0.94942, 0.897884, 0.838982, 0.792948, 0.748738, 0.700858, 0.64743, 0.601348,

0.557104, 0.520179, 0.494297, 0.470212, 0.451642, 0.434836, 0.427248,

0.417788, 0.411977, 0.404409, 0.404133, 0.400248, 0.396329, 0.391912,

0.387502, 0.390417, 0.384196 ]; cd2coast_mach = [ 1.981417, 2.072454, 2.163592, 2.273011, 2.409801, 2.519288,

2.720213, 2.875654, 3.058466, 3.268885, 3.552429, 3.790319, 4.174695,

4.467597, 4.842983, 5.181672, 5.575339, 5.89578, 6.371763, 6.976083,

7.992453, 8.981484, 9.503388, 9.970415 ]; cd2coast = [ 0.687863, 0.658385, 0.634421, 0.608606, 0.577257, 0.555118,

0.525559, 0.512578, 0.494061, 0.482877, 0.464287, 0.453083, 0.439933,

0.432365, 0.428413, 0.420811, 0.415007, 0.411095, 0.399716, 0.395595,

0.389333, 0.390444, 0.386384, 0.386041 ];

Page 74: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

74 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%actual values actual_alt_time = [ 0, 41.737444, 57.743486, 73.714966, 86.489462,

108.876031, 131.291402, 154.785876, 183.670099, 219.025096, 243.690837,

255.501437, 273.763609, 303.874783, 334.02052, 352.351815, 378.236826,

396.612285, 413.912481, 460.459802 ]; actual_alt = [ 0, 25.2797111, 44.62400112, 71.07046852, 92.78003292,

124.360085, 150.0216563, 174.5002385, 194.2475645, 207.6860784, 212.0425324,

211.2611662, 208.1166424, 196.2994453, 177.3800708, 160.0311941, 134.4013864,

107.977506, 81.9474849, 1.091937348 ]*1000;

actual_range_88d = [ 0.583300364, 8.05804274, 14.40963231, 19.61310966,

23.68696332, 26.59976485, 31.26801235, 37.7092702, 43.58201776, 46.53641706,

51.84157848, 57.76701729, 64.89048527, 68.46238766 ]*1000; actual_alt_88d = [ 1.183061304, 85.71732721, 140.1054705, 180.3062159,

194.4982845, 202.7778469, 211.0602094, 208.1151627, 194.5300315, 176.2117217,

151.395444, 104.1196752, 39.11385849, 0.10924948 ]*1000; actual_range_80d = [ 0.584224512, 9.328175824, 19.82202452, 35.57481798,

51.33223218, 66.51004445, 85.19874869, 105.0679177, 128.4581481, 145.418214,

164.735513, 184.6462816, 211.6010175, 237.9853966, 259.1071362, 293.15761

]*1000; actual_alt_80d = [ 0.591997356, 21.88430246, 46.72578962, 76.30419274,

102.9272761, 126.0030424, 149.0844128, 165.6659467, 175.7513831, 181.6890988,

176.9914026, 166.9750643, 142.7843996, 109.1357802, 73.1145024, 1.649935688

]*1000; actual_range_70d = [ 1.75544598, 8.761513828, 19.27570119, 31.54625868,

50.83027906, 68.94862471, 88.24189027, 106.9537056, 129.1754869, 151.9861135,

178.8974032, 209.3288302, 232.1588694, 256.7499032, 281.3427834, 300.6721,

321.7624093, 343.4387914, 371.5712215]*1000; actual_alt_70d = [ 0.002802076, 10.06209194, 21.90017595, 33.14999623,

49.7305985, 63.35401236, 74.02397515, 82.32874874, 91.23018857, 97.76830602,

101.3576431, 99.04194124, 93.16771949, 83.74991612, 73.14998486, 60.76845738,

44.84335014, 28.32811051, 0]*1000;

actual_acc_v_t_100 = [ 0, 2.594975, 2.459186, 3.801842, 5.440991, 6.613576,

8.129392, 10.410322, 13.167596, 15.869896, 20.339823, 25.291242, 30.18923,

34.863717, 39.42671, 44.066297, 50.165284]; actual_acc_100 = [ 10.244633, 11.548902, 2.753933, 2.641376, 2.613903,

2.636217, 2.462179, 2.372366, 2.465167, 2.643697, 3.063636, 3.788505,

4.635797, 5.740384, 6.979734, 8.647083, 11.583942]; actual_acc_v_t_200 = [ 0, 2.572069, 2.394174, 3.706769, 5.112636, 6.695008,

8.067211, 9.762878, 12.10599, 14.56883, 17.035789, 20.034066, 22.916731,

27.099947, 32.289794, 36.661097, 41.217399, 44.362171, 50.130179]; actual_acc_200 = [ 9.651237, 11.004595, 2.601145, 2.470294, 2.467715,

2.48316, 2.376665, 2.300159, 2.295859, 2.352503, 2.507, 2.758382, 3.046675,

3.61393, 4.436222, 5.296714, 6.377052, 7.325423, 9.357678];, actual_acc_v_t_300 = [ 0, 2.607741, 2.446317, 3.791548, 5.137807, 6.486126,

7.771234, 9.524964, 11.457001, 13.391613, 15.797934, 19.084982, 22.494847,

25.907801, 29.970773, 34.275262, 38.582325, 42.659195, 45.854824, 50.004169]; actual_acc_300 = [ 9.290243, 10.46018, 2.448142, 2.396743, 2.369808,

2.391799, 2.303813, 2.214967, 2.186957, 2.220105, 2.325783, 2.478775, 2.7661,

3.126814, 3.620895, 4.285788, 5.011839, 5.836174, 6.600962, 7.755443];

long_dim =[ 0, 0, 0, 0.657269379, 1.004958264, 4.956194304, 5.238861821,

5.545076997, 5.870241203, 6.284911372, 6.652543586, 6.944781223, 7.482314149

];

Page 75: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

75 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

lat_dim =[ 0, 0.371603981, 1.18255354, 1.240819566, 0.407109422, 0.360945735,

0.363901634, 0.367104778, 0.333011932, 0.299854518, 0.238086138, 0.184901992,

0 ];

t_drag_chute = [ 0, 1.8, 2.4, 3.6, 4.8, 5.4, 12, 10000]; drag_chute_SCd = [ 6.347942784, 6.347942784, 6.347942784, 6.347942784,

126.9588557, 105.7990464, 105.7990464, 105.7990464]*0.015; time_chute = 1000;

%Initial Conditions Initial_Altitude = 5; %Rocket Initial Altitude, [m] Earth_Radius = 6378137; %Equatorial Radius, [m] Gravity = 9.80665; %Gravitatinal Acceleration, [m/s.s] Air_Density = 1.2250; %Air Density at 15C ISO standard sea level, [kg/m^3] R = 8.3145; %molar_gas_contant, [kJ/kg.K] M_air = 0.0289645; %air_molar_mass, kg/mol gamma = 1.4; %adiabatic_index S_CD_chute = 105.8*0.025; %parachute characteristic area drag, [m^2] launch_angle = 88; % degrees from horizontal time = 0;

pitch1=1; %Pitch1 time, [s] pitch2=1.1; %Pitch2 time, [s]

%run simulink model t_stop=1000; %[s] T_s=t_stop/4000; %[s] options=simset('solver','ode5','fixedstep',T_s); sim('rocket.mdl',t_stop,options); % sim('rocket.mdl')

%maximum and minimum altitudes [Sy_max,Sy_max_i]=max(Sy); % [m] Sy_max_time = time(Sy_max_i); Sy_min=min(Sy); % [m] Sy_max

%maximum and minimum horizontal distance Sx_max=max(Sx); % [m] Sx_min=min(Sx); % [m]

%maximum acceleration calculation - outputs to command window A=sqrt(Ax.^2+Ay.^2); % [m/s.s] max_A=max(A)/Gravity; %Gs, [-] max_A

%maximum velocity calculation - outputs to command window V=sqrt(Vx.^2+Vy.^2); % [m/s.s] max_V=max(V); % [m/s.s] max_V

Total_Burn_Time % [s]

%Stability derivatives b = Diameter; % Characteristic length, m

Page 76: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

76 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

S = pi*(b^2)/4; % Characteristic surface, m^2 Tail_station = 7.15; % m epsilon = long_dim(end)-CG_inst; Cz_alpha = -Cl; Cm_alpha = -Cp_station/b.*Cz_alpha; Cm_q = 2*Cz_alpha.*((-CG_inst-Tail_station)/b).^2; % Z_alpha = q_bar*S.*Cz_alpha; M_alpha = q_bar*S*(b/2).*Cm_alpha; M_q = q_bar*S*(b/2)^2*S.*Cm_q./Ue;

%generates vertical line on trajectory plot to determine rocket's position %at end of burn time brnvtime=Total_Burn_Time*ones(301,1); brnvals=[Sy_min:(Sy_max-Sy_min)/300:Sy_max]';

%mach 1 line [q_max,time_q_max]=max(q_bar(1:length(q_bar)/2)); q_max_time=time(time_q_max)*ones(3,1); q_max_vals=[Sy_min:(Sy_max-Sy_min)/2:Sy_max]'; Mach(isinf(Mach)) = 0; [c, i_mach_1] = min(abs(Mach-1)); time_mach_1 = time(i_mach_1)*ones(3,1); mach_1_vals=[Sy_min:(Sy_max-Sy_min)/2:Sy_max]';

%altitude plot of trajectory % figure(1) figure('units','normalized','outerposition',[0 0 1 1]) subplot(321) hold on plot(time,Sy/1000,brnvtime,brnvals/1000,'r',time_mach_1,mach_1_vals/1000,'r-

.',q_max_time,q_max_vals/1000,'r:.') plot(actual_alt_time,actual_alt/1000,'g-o') % %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) x1 = Sy_max_time; y1 = Sy_max+10000; txt1 = sprintf(' max. alt. = %0.0f km, t = %0.f

s',Sy_max/1000,Sy_max_time); text(x1,y1,txt1) grid on xlabel('Time (seconds)') ylabel('Altitude (km)') title('Altitude vs. Time','fontweight','bold') legend('Rocket Altitude','End of Powered Flight','Mach 1','Max Q','Real',4) hold off %acceleration vs. time subplot(323) plot(time,(Ay.^2+Ax.^2).^0.5/Gravity, 'b', actual_acc_v_t_200,

actual_acc_200, 'g-o') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Acceleration (g)') title('Acceleration vs. Time','fontweight','bold')

%velocity vs time

Page 77: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

77 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

subplot(325) plot(time,V) %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Airspeed (m/s)') title('Velocity vs. Time','fontweight','bold')

%thrust vs time subplot(322) plot(time,Thrust/1000) %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Thrust (kN)') title('Thrust Force vs. Time','fontweight','bold')

%drag vs time subplot(324) plot(time,Drag/1000) %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Drag (kN)') title('Drag Force vs. Time','fontweight','bold')

%fx & fy vs time subplot(326) plot(time,Fx/1000,'b',time,Fy/1000,'r') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Fx, Fy (kN)') title('Radial Force & Tangential Force vs. Time','fontweight','bold') legend('Fx','Fy',4)

% figure(2) figure('units','normalized','outerposition',[0 0 1 1]) %mass vs time subplot(321) plot(time,Mass,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('mass (kg)') title('Mass vs. Time','fontweight','bold')

%impulse vs time subplot(323) plot(time,Impulse_Ratio*Total_Impulse/1000,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('I_T (kN.s)') title('Impulse vs. Time','fontweight','bold')

Page 78: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

78 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%CG vs time subplot(325) plot(time,CG_inst,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('CG (m)') title('CG station vs. Time','fontweight','bold')

%Roll moment of inertia vs time subplot(322) plot(time,Jxx_inst,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Jxx (kg.m^2)') title('Roll moment of inertia vs. Time','fontweight','bold')

%Pitch/Yaw moment of inertia vs time subplot(324) plot(time,Jyyzz_inst,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('Jyyzz (kg.m^2)') title('Pitch/Yaw moment of inertia vs. Time','fontweight','bold')

%Cp station vs time subplot(326) plot(time,Cp_station,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (seconds)') ylabel('CP_s_t_a_t_i_o_n (m)') title('CP station vs. Time','fontweight','bold')

%2D plot of trajectory % figure(3) figure('units','normalized','outerposition',[0 0 1 1]) subplot(321) plot(Sx/1000,Sy/1000, 'b',actual_range_88d/1000, actual_alt_88d/1000, 'g-o') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) %set(gca,'XTickLabel',num2str(get(gca,'XTick').')) grid on xlabel('Radial Downrange position (km)') ylabel('Altitude position (km)') title('Altitude vs. Radial','fontweight','bold') str = sprintf('Rocket Position with launch angle %0.0f °, max altitude %0.0f

m',launch_angle, max(Sy)); legend(str,'Real','Location','southwest')

%theta plot subplot(323) plot(time,theta*180/pi,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on

Page 79: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

79 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

xlabel('Time (seconds)') ylabel('Theta [°]') title('Theta vs. Time','fontweight','bold')

%rocket plot subplot(325) hold on plot(long_dim,lat_dim,'b') x_inst_CG = long_dim(end)-CG_inst; y_inst_CG = zeros(length(CG_inst),1); sample = 20; plot(x_inst_CG(1:round(length(x_inst_CG)/sample):length(x_inst_CG)),y_inst_CG

(1:round(length(x_inst_CG)/sample):length(x_inst_CG)),'go') x_inst_CP = long_dim(end)-Cp_station; y_inst_CP = zeros(length(Cp_station),1); plot(x_inst_CP(1:round(length(x_inst_CP)/sample):length(x_inst_CP)),y_inst_CP

(1:round(length(x_inst_CP)/sample):length(x_inst_CP)),'r+') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Longitudinal (m)') ylabel('Lateral (m)') title('Rocket Cross-section','fontweight','bold') legend('Rocket','CG','CP') hold off

%Z_alpha plot subplot(322) plot(time,Z_alpha,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Z_\alpha (N/rad)') title('Z\alpha stability derivative','fontweight','bold')

%M_alpha plot subplot(324) plot(time,M_alpha,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('M_\alpha (N.m/rad)') title('M\alpha stability derivative','fontweight','bold')

%M_q plot subplot(326) plot(time,M_q,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('M_q (N.m.s/rad)') title('M_q stability derivative','fontweight','bold')

%rocket cg shift plot + theta + trajectory % subplot(324) % figure(4) figure('units','normalized','outerposition',[0 0 1 1]) hold on

Page 80: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

80 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

dt = 100; ColorSet = varycolor(int8(length(time)/dt+1)); k=1; length(time) plot(actual_range_88d/1000, actual_alt_88d/1000, 'g-o') % plot(actual_range_80d, actual_alt_80d, 'g-o') % plot(actual_range_70d, actual_alt_70d, 'g-o') lat_dim_rev = fliplr(lat_dim); rocket_scale = 1.0; for i = 1:dt:length(time) long_dim_cg_t = long_dim - long_dim(end) +

CG_inst(i)*ones(1,length(long_dim)); R=rotz(theta(i)*180/pi); for j = 1:length(long_dim_cg_t) rocket(j,:) = (R*[long_dim_cg_t(j)*rocket_scale ;

lat_dim(j)*rocket_scale ; 0])'; rocketm(j,:) = (R*[long_dim_cg_t(j)*rocket_scale ; -

lat_dim(j)*rocket_scale ; 0])'; end plot(rocket(:,1) + Sx(i)/1000,rocket(:,2) + Sy(i)/1000, 'Color',

ColorSet(k,:)) plot(rocketm(:,1) + Sx(i)/1000,rocketm(:,2) + Sy(i)/1000, 'Color',

ColorSet(k,:)) k=k+1; x1 = Sx(i)/1000; y1 = Sy(i)/1000; txt1 = sprintf(' t = %0.2f',time(i)); text(x1,y1,txt1) end % %set(gca,'XTick',round(Sx(1:round(length(Sx)/10):length(Sx)))) % get(gca,'XTick') axis equal xlim([0 Sx(end)/1000*1.40]) ylim([0 max(Sy)/1000*1.10]) %set(gca,'XTickLabel',num2str(get(gca,'XTick').')) %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) % axis([0,70000,0,300000]) grid on xlabel('Downrange (km)') ylabel('Altitude (km)') title('Rocket Orientation, Altitude and Range','fontweight','bold') % legend off % set(gcf, 'Colormap', ColorSet); % colorbar hold off

%environmental digital telemetry % figure(5) figure('units','normalized','outerposition',[0 0 1 1]) %gravity subplot(321) plot(time,grav_h,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Gravity (m/s.s)') title('Gravity over flight path time','fontweight','bold')

Page 81: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

81 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%Temperature subplot(322) plot(time,Temp,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Temperature (K)') title('Temperature over flight path time','fontweight','bold')

%Wind Speed subplot(323) plot(time,Sound_speed,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Sound speed (m/s)') title('Sound speed over flight path time','fontweight','bold')

%Pressure altitude subplot(324) plot(time,Pressure_alt/1000,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Ambient Pressure (kPa)') title('Ambient Pressure over flight path time','fontweight','bold')

%Density subplot(325) plot(time,Density,'b') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Density (m/s.s)') title('Air density over flight path time','fontweight','bold')

%Mach subplot(326) plot(time,Mach,'b') ylim([0 20]) %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('Mach (-)') title('Mach number over flight path time','fontweight','bold')

%Dynamic Pressure figure('units','normalized','outerposition',[0 0 1 1]) [q_bar_max_launch, q_bar_max_launch_i] = max(q_bar(1:length(q_bar)/2)); subplot(321) plot(time,q_bar/1000,'b',time(q_bar_max_launch_i),q_bar_max_launch/1000,'ro') %set(gca,'YTickLabel',num2str(get(gca,'YTick').')) grid on xlabel('Time (s)') ylabel('q_bar (N/m^2)')

Page 82: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

82 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

title('Dynamic Pressure over flight path time','fontweight','bold') str = sprintf('Max Dynamic Pressure Design Point:\n q_b_a_r %0.0f N/m^2,\n

time %0.0f s,\n altitude %0.0f m,\n airspeed %0.0f m/s,\n Mach %0.2f,\n mass

%0.2f kg,\n Z\\alpha %0.2f N/rad,\n M\\alpha %0.2f N.m/rad,\n M_q %0.2f

N.m.s/rad,\n epsilon %0.2f m,\n b %0.2f m,\n S %0.2f m^2,\n theta %0.2f °,\n

Thrust %0.2f N,\n Jyy %0.2f kgm^2',... q_bar_max_launch, time(q_bar_max_launch_i), Sy(q_bar_max_launch_i),

Ue(q_bar_max_launch_i), Mach(q_bar_max_launch_i), Mass(q_bar_max_launch_i),

... Z_alpha(q_bar_max_launch_i), M_alpha(q_bar_max_launch_i),

M_q(q_bar_max_launch_i), epsilon(q_bar_max_launch_i), b, S,

theta(q_bar_max_launch_i)*180/pi, ... Thrust(q_bar_max_launch_i), Jyyzz_inst(q_bar_max_launch_i)); str % legend('q_b_a_r',str,'Location','southwest') legend('q_b_a_r','max Q','Real','Location','northwest'); a11 =

Z_alpha(q_bar_max_launch_i)/Mass(q_bar_max_launch_i)/Ue(q_bar_max_launch_i); a12 = -

grav_h(q_bar_max_launch_i)*sin(theta(q_bar_max_launch_i))/Ue(q_bar_max_launch

_i); a13 = 1; a21 = 0; a22 = 0; a23 = 1; a31 = M_alpha(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_launch_i); a32 = 0; a33 = M_q(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_launch_i); %pitch dynamics A = [a11 a12 a13; a21 a22 a23; a31 a32 a33]; damp(A) b1 =

Thrust(q_bar_max_launch_i)/Mass(q_bar_max_launch_i)/Ue(q_bar_max_launch_i); b2 = 0; b3 =

Thrust(q_bar_max_launch_i)*epsilon(q_bar_max_launch_i)/Jyyzz_inst(q_bar_max_l

aunch_i); B = [b1 b2 b3]'; C = [0 1 0]; D = 0; %Regulator design by LQR [k,S,E] = lqr(A,B,[0.01 0 0; 0 0.1 0;0 0 0.1],1) %Observer (kalman filter) design by LQR Lp = lqr(A',C',eye(3),1);L = Lp' %Augmented plant with gimbal servo Abar = [A B; zeros(1,3) -time(q_bar_max_launch_i)] Bbar = [0 0 0 time(q_bar_max_launch_i)]' Cbar = [C 0] %Servo augmented closed-loop system Ac = [Abar -Bbar*k;L*Cbar A-L*C-B*k] Bc = [Bbar*k; B*k] %Closed loop system with pitch angle output sys = ss(Ac, Bc(:,2), [0 1 0 zeros(1,4)],0) %Closed loop initial response figure [y,t,x] = initial(sys,[0.1 0 0 0 0 0 0]'); plot(t,x(:,1)*180/pi,'b',t,x(:,2)*180/pi,'g',t,x(:,3)*180/pi,'r',t,x(:,4)*180

/pi,'c'), grid

Page 83: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

83 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

legend('\alpha [deg]','\theta [deg]','q [deg/s]','d\mu [deg]') title('Closed-loop initial response with gimbal servo of pitch control system

at design point (max Q)','fontweight','bold') %Closed loop frequency response with gain and phase gains figure margin(sys) figure bode(sys), grid Test = feedback(sys,1); pole(Test) figure rlocus(sys) figure k1 = 1/2; Test1 = feedback(sys*k1,1); k2 = 2; Test2 = feedback(sys*k2,1); k3 = 10; Test3 = feedback(sys*k3,1); k4 = 20; Test4 = feedback(sys*k4,1); k5 = 31; Test5 = feedback(sys*k5,1); step(Test,'b',Test1,'r',Test2,'g',Test3,'y',Test4,'c',Test5,'m',12), legend('k = 1','k = 1/2','k = 2','k = 10','k = 20','k = 31') % m = allmargin(Test) % GainMargins_dB = mag2db(m.GainMargin) % step(Test), title('Closed-loop response for k=1') sysl = tf(sys)

%Closed loop pitch control system inputs %T_s % step size %time % domain %theta % range %desired pitch rate [c, t_i] = min(abs(time-5.0)); [c, t_f] = min(abs(time-50.0)); td_Qd = diff(theta)/T_s; % first derivative figure [AX,H1,H2] = plotyy(time, theta,time(1:length(td_Qd)),td_Qd); grid on xlabel('Time (s)') ylabel(AX(1),'theta (rad)') ylabel(AX(2),'Qd (rad/s)') % ylabel('Qd (rad/s)') % yylabel('theta (rad)') title('Pitch rate over flight path time','fontweight','bold')

td_gamd = theta(t_i:t_f); td_m = Mass(t_i:t_f); td_v = Ue(t_i:t_f); td_Jyy = Jyyzz_inst(t_i:t_f); td_Za = Z_alpha(t_i:t_f); td_Ma = M_alpha(t_i:t_f); td_Mq = M_q(t_i:t_f);td_Mq(1)=0; td_T = Thrust(t_i:t_f); td_x = epsilon(t_i:t_f); td_g = grav_h(t_i:t_f); % time td = time(t_i:t_f); td_Qd = td_Qd(t_i:t_f);

Page 84: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

84 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%run simulink model t_stop=50; %[s] T_s=t_stop/1000; %[s] options=simset('solver','ode5','fixedstep',T_s); sim('closed_loop_pitch_control_system',t_stop,options);

l=1; for j=1:3 ts = 5*2^(1-j); % settling time, [s] k1 = (32*td_m.*td_v.*td_Jyy./ts^2+(td_m.*td_v.*td_Ma +(td_Mq-

td_m.*td_v.*td_x).*... (td_Za+8*td_m.*td_v/ts+td_m.*td_v.*td_Mq./td_Jyy)))./... (td_T.*(td_x.*td_Za-td_Ma+(td_m.^2).*(td_v.^2).*(td_x.^2)./td_Jyy-

td_m.*td_v.*td_x.*td_Mq./td_Jyy)); k2 = -

(td_Za+8*td_m.*td_v/ts+td_m.*td_v.*(td_Mq+td_T.*td_x.*k1)./td_Jyy)./td_T; k12(:,l)=k1;k12(:,l+1)=k2; acc_xn = CG_inst-2.2; %nose accelerometer location td_xn = acc_xn(t_i:t_f); Kbar=[]; for i=1:size(td,1) A=[td_Mq(i,1)/td_Jyy(i,1) td_Ma(i,1)/td_Jyy(i,1); 1

td_Za(i,1)/(td_m(i,1)*td_v(i,1))]; B=-td_T(i,1)*[td_x(i,1)/td_Jyy(i,1); 1/(td_m(i,1)*td_v(i,1))]; C=[1 0; -td_Mq(i,1)*td_xn(i,1)/td_Jyy(i,1) td_Za(i,1)/td_m(i,1)-

td_Ma(i,1)*td_xn(i,1)/td_Jyy(i,1)]; D=[0; td_T(i,1)*(td_xn(i,1)*td_x(i,1)/td_Jyy(i,1)-1/td_m(i,1))]; K=[k1(i,1) k2(i,1)]; Kb=K*inv(C-D*K); Kbar(i,:)=Kb; end k12bar(:,l)=Kbar(:,1);k12bar(:,l+1)=Kbar(:,2);l=l+2; end figure %State feedback gains subplot(211) plot(td, k12(:,1),'b+',td, k12(:,2),'g+',td, k12(:,3),'b.',td,

k12(:,4),'g.',td, k12(:,5),'bo',td, k12(:,6),'go') grid on xlabel('Time (s)','fontweight','bold') ylabel('K_q, K_\alpha (-)','fontweight','bold') title('State feedback gains over sustainer phase','fontweight','bold') legend('t = 5[s]','t = 5[s]', 't = 10[s]','t = 10[s]','t = 20[s]','t =

20[s]') %Output feedback gains subplot(212) plot(td, k12bar(:,1),'b+',td, k12bar(:,2),'g+',td, k12bar(:,3),'b.',td,

k12bar(:,4),'g.',td, k12bar(:,5),'bo',td, k12bar(:,6),'go') ylim([-2 2]) legend('t = 5[s]','t = 5[s]', 't = 10[s]','t = 10[s]','t = 20[s]','t =

20[s]') grid on xlabel('Time (s)','fontweight','bold') ylabel('K_q^o, K_\alpha^o (-)','fontweight','bold') title('Output feedback gains over sustainer phase','fontweight','bold')

Page 85: 1 of 85 · 1 of 85 Mircea-Vlad Radulescu MECH6251 April 19th 2016 Concordia University th April 19 2016 MECH 6251 Space Flight Dynamics and Propulsion Systems Mircea-Vlad Radulescu

85 of 85

Mircea-Vlad Radulescu MECH6251 April 19th 2016

%root locus for ts=5[s] over flight time figure ColorSet = varycolor(length(td)); hold on for j=1:3 % ts = 5; % settling time, [s] ts = 5*2^(1-j); % settling time, [s] for i=1:size(td,1) A=[td_Mq(i,1)/td_Jyy(i,1) td_Ma(i,1)/td_Jyy(i,1); 1

td_Za(i,1)/(td_m(i,1)*td_v(i,1))]; B=-td_T(i,1)*[td_x(i,1)/td_Jyy(i,1); 1/(td_m(i,1)*td_v(i,1))]; C=[1 0; -td_Mq(i,1)*td_xn(i,1)/td_Jyy(i,1) td_Za(i,1)/td_m(i,1)-

td_Ma(i,1)*td_xn(i,1)/td_Jyy(i,1)]; D=[0; td_T(i,1)*(td_xn(i,1)*td_x(i,1)/td_Jyy(i,1)-1/td_m(i,1))]; sys = ss(A,B,C,D); e(i,:) = eig(sys); end k=1; for i = 2:length(td) plot(e(i,1),e(i,2),'o','Color', ColorSet(k,:)) k=k+1; if mod(i,25)==0 x1 = e(i,1); y1 = e(i,2); txt1 = sprintf(' t = %0.2f',time(i)); text(x1,y1,txt1) end end axes_x = [min(e(:,1))*1.5 max(e(:,1))*1.5]; axes_y = [min(e(:,2))*1.5 max(e(:,2))*1.5]; plot(axes_x,[0 0],'r',[0 0],axes_y,'r') end grid on hold off