+ All Categories
Home > Documents > Path Planning UAV Sinus

Path Planning UAV Sinus

Date post: 20-Feb-2015
Category:
Upload: al-wasim
View: 176 times
Download: 1 times
Share this document with a friend
96
PATH PLANNING AND CONTROL OF UNMANNED AERIAL VEHICLES IN THE PRESENCE OF WIND By Andrew Charles Vaughn B.S. (University of Illinois, Urbana-Champaign) 2002 A report submitted in partial satisfaction of the requirements for the degree of Master of Science, Plan II in Mechanical Engineering at the University of California at Berkeley Committee in charge: Professor J. Karl Hedrick, Chairman Professor Raja Sengupta Fall 2003
Transcript
Page 1: Path Planning UAV Sinus

PATH PLANNING AND CONTROL OF UNMANNED AERIAL VEHICLES IN THE PRESENCE OF WIND

By

Andrew Charles Vaughn

B.S. (University of Illinois, Urbana-Champaign) 2002

A report submitted in partial satisfaction of the requirements for the degree of

Master of Science, Plan II

in

Mechanical Engineering

at the

University of California at Berkeley

Committee in charge: Professor J. Karl Hedrick, Chairman

Professor Raja Sengupta

Fall 2003

Page 2: Path Planning UAV Sinus
Page 3: Path Planning UAV Sinus

1

Abstract

Path planning and Control of Unmanned Aerial Vehicles in the Presence of Wind

by

Andrew Charles Vaughn

Master of Science in Mechanical Engineering

University of California, Berkeley

Professor J. Karl Hedrick, Chair

This thesis presents strategies for path planning of unmanned aerial vehicles

(UAVs) to track a moving target or point of interest. The UAVs are constrained in their

turn rate and speed. The motion of the point of interest is unconstrained and is not

predefined. Trajectories are developed based on the velocities of the UAV and the point

of interest. The trajectory generation is first given for one UAV and then expanded to

multiple UAVs flying in formation. Stable control laws were developed for the UAVs

and the formation to track the desired trajectory. Simulation and experimental results

confirm the approaches within this thesis. In order to improve the tracking of the desired

trajectories, wind disturbance rejection controls are examined. The current autopilot is

enhanced using several sensor feedback techniques. H2 and H∞ control theory is outlined

and applied to the problem of wind disturbances. Actuator bandwidth and sensor noise

constraints are included in the design process. The new control laws are tested, with

some evidence that H∞ control may help improve the control of the UAV in the presence

of wind.

Page 4: Path Planning UAV Sinus

To Natalie

Page 5: Path Planning UAV Sinus

i

Contents

List of Figures iii 1 Introduction 1 1.1 Motivation and Background .......................................................................... 1 1.2 Organization................................................................................................... 3 2 Path Planning for a Single UAV 4 2.1 Introduction.................................................................................................... 4 2.2 Path Planning Algorithm................................................................................ 4 2.3 Wind Compensation....................................................................................... 9 2.4 Simulation Implementation and Results ........................................................ 9 2.5 Experimental Results ..................................................................................... 15 3 Orbital Trajectory Specification for Multiple UAVs 19 3.1 Introduction.................................................................................................... 19 3.2 Orbital Trajectory Theory.............................................................................. 20 3.2.1 Definition ........................................................................................... 20 3.2.2 Parameterization ................................................................................ 22 3.2.3 Orbit Control...................................................................................... 28 3.3 Formation Control.......................................................................................... 30 3.4 Simulation Results ......................................................................................... 31 3.5 Experimental Results ..................................................................................... 32 4 Disturbance Rejection Control 36 4.1 Introduction.................................................................................................... 36 4.2 Overview of Aircraft Dynamics..................................................................... 37 4.3 Simulation Environment ................................................................................ 40 4.4 Current Autopilot ........................................................................................... 41 4.5 Enhancement of Current Autopilot................................................................ 47 4.5.1 Utilization of Additional Sensors....................................................... 47 4.5.2 Alternative Usage of Rate Gyros ....................................................... 50 4.5.3 Comparison of Enhancement Techniques ......................................... 51 4.6 H2 Control Theory.......................................................................................... 53 4.7 H∞ Control Theory......................................................................................... 56 4.8 Weighting Functions...................................................................................... 58

Page 6: Path Planning UAV Sinus

ii

4.8.1 Actuator Models and Weights ........................................................... 59 4.8.2 Sensor Models and Weights............................................................... 60 4.8.3 Wind Model and Weights .................................................................. 62 4.8.4 Autopilot Command Weight.............................................................. 65 4.8.5 Ideal Command Response.................................................................. 66 4.8.6 Performance Weights......................................................................... 67 4.9 Interconnected System ................................................................................... 69 4.10 Simulation Results and Discussion................................................................ 71 4.10.1 H2 Control Simulation and Results .................................................... 71 4.10.2 H∞ Control Simulation and Results ................................................... 74 4.11 Gain-scheduling H∞ Control .......................................................................... 79 4.12 Future Work ................................................................................................... 83 5 Conclusions 84 Bibliography 86

Page 7: Path Planning UAV Sinus

iii

List of Figures

2.1 Top view of path planning algorithm in sinusoidal mode ............................. 5 2.2 Speed ratio, s , vs amplitude/distance, A/D1, ratio of path planning .............. 7 2.3 Top view of path planning algorithm in the rose curve loitering mode ........ 8 2.4 Piccolo miniature avionics system................................................................. 10 2.5 Piccolo ground station.................................................................................... 10 2.6 Hardware-in-the-loop (HIL) simulation schematic with 3 aircraft................ 10 2.7 Point of interest (POI) defined in terms of the ground vehicle...................... 11 2.8 Simulation of UAV and ground vehicle with no wind .................................. 13 2.9 Simulation with no wind compensation, 10 m/s south wind ......................... 13 2.10 Simulation with wind compensation, 10 m/s south wind .............................. 14 2.11 Simulation with no wind and changing speed in the ground vehicle ............ 14 2.12 Diagram of experimental setup with 3 aircraft .............................................. 15 2.13 Data from the entire experiment, with the UAV following a truck ............... 16 2.14 Close up of experimental data highlighting loitering mode .......................... 17 2.15 Close up of experimental data highlighting sinusoidal mode........................ 17 2.16 Picture of video taken from a camera on the bottom of the UAV ................. 18 3.1(a) Lemniscate trajectory in POI coordinates...................................................... 21 3.1(b) Lemniscate trajectory in fixed reference frame coordinates.......................... 21 3.2 Trajectory parameter assignment algorithm .................................................. 26 3.3 Trajectories in the POI coordinate frame....................................................... 26 3.4 Values of p versus VP and VT ......................................................................... 27 3.5 Values of A versus VP and VT......................................................................... 27 3.6 Control law development for a single UAV following an orbit trajectory.... 29 3.7 Illustration of orbit trajectory and the formation ........................................... 30 3.8 Simulation with 3 UAVs tracking a ground vehicle, varying speed.............. 31 3.9 Simulation with 3 UAVs tracking a ground vehicle, changing heading........ 32 3.10 Picture of Rascal experimental UAV platform.............................................. 33 3.11 Top view of experiment with UAV and ground vehicle paths ...................... 33 3.12 Ground coverage plot from the UAV cameras .............................................. 34 3.13 Picture of three UAVs flying in formation .................................................... 35 4.1 Aircraft velocities, forces, and moments in body-axes.................................. 38 4.2 Picture of the Aerosonde UAV...................................................................... 40 4.3 Simulink diagram of the aircraft simulation .................................................. 41 4.4 Complete Simulink simulation setup with Piccolo autopilot......................... 42

Page 8: Path Planning UAV Sinus

iv

4.5 Bank angle to turning radius in coordinated turn flight................................. 44 4.6 Simulation of current autopilot for wind = 0 ................................................. 46 4.7 Simulation of current autopilot for wind = 5 m/s .......................................... 46 4.8 Washout filter placed on the accelerometer and roll angle............................ 48 4.9 Simulation of current autopilot with enhancement of ay integral, no wind ... 49 4.10 Simulation of current autopilot with enhancement of ay integral, wind ........ 49 4.11 Simulation of current autopilot with filtered roll enhancement, no wind...... 50 4.12 Simulation of current autopilot with filtered roll enhancement, wind........... 51 4.13 Comparison of the three controllers with no wind......................................... 52 4.14 Comparison of the three controllers with 5 m/s wind.................................... 52 4.15 General control configuration with generalized plant, P, and controller, K .. 54 4.16 Model of actuator with delay and mechanical model .................................... 59 4.17 Frequency response of sensor models............................................................ 62 4.18 Frequency response of the side gust velocity weighting function ................. 64 4.19 Frequency response of the roll gust velocity weighting function .................. 65 4.20 Frequency response of the autopilot command weighting function .............. 66 4.21 Step response of the ideal second-order system ............................................ 67 4.22 Frequency response of the yaw rate error weighting function....................... 68 4.23 Generalized control configuration ................................................................. 69 4.24 The interconnected system comprised of all of the weights and models....... 70 4.25 Representation of the controller, K, with input and output signals................ 70 4.26 Hankel singular values of the H2 controller, K2, with the balanced states..... 71 4.27 H∞ norm of the closed loop system with the reduced controller, K2red .......... 72 4.28 Yaw rate response for the linear aircraft model with the controller K2red ...... 73 4.29 Response of the nonlinear system with the discrete controller K2red ............. 73 4.30 Hankel singular values of the H∞ controller, K∞, with the balanced states.... 75 4.31 H∞ norm of the closed loop system with the reduced controller, K∞red ......... 75 4.32 Yaw rate response for the linear aircraft model with the controller K∞red ..... 76 4.33 Response of the nonlinear system with the discrete controller, K∞red............ 76 4.34 Response of the nonlinear system with the continuous controller, K∞red....... 77 4.35 Response of the nonlinear system with continuous controller, K∞new............ 78 4.36 H∞ gain scheduler.......................................................................................... 79 4.37 Simulation of gain scheduling discrete H∞ controller, no wind..................... 80 4.38 Simulation of gain scheduling discrete H∞ controller, wind.......................... 81 4.39 Comparison of autopilot and gain scheduling H∞ controller, no wind .......... 82 4.40 Comparison of autopilot and gain scheduling H∞ controller, wind ............... 82

Page 9: Path Planning UAV Sinus

v

Acknowledgements

Much thanks goes to all of the people in the Vehicle Dynamics Lab (VDL) and

the Center for Collaborative Control of Unmanned Vehicles (C3UV) who made this

research experience very enjoyable. In particular, Professor J. Karl Hedrick and

Professor Raja Sengupta assisted greatly in forming a great research project and group,

and provided valuable advice whenever needed. Particular individuals who deserve

special notice for their help in this research are Xiao Xiao, Jusuk Lee, Stephen Spry, Tim

McGee, and Eric Frew.

This work was supported, in part, by the Office of Naval Research (ONR) under

STTR Phase I Grant N00014-02-M-0236 and the 6.1 AINS Funding Program.

Page 10: Path Planning UAV Sinus

1

Chapter 1

Introduction

1.1 Motivation and Background

Path planning for unmanned aerial vehicles (UAVs) is not a new concept by any

means. People, especially the military, have been using UAVs to perform surveillance

activities for a long time. Today, UAVs are becoming increasingly popular to perform

more sophisticated missions that include surveillance, sensing, and combat routines [10,

13, 18]. UAVs are particularly useful in these applications because they minimize the

risk for loss of human life, they are able to perform monotonous duties for long periods

of time, and they are able to be operated by a limited number of personnel (many UAVs

operated by one person). As the missions become more demanding, UAVs need to have

better path planning techniques. This means that the control has to be refined in order to

have better tracking capabilities.

The operational needs of the UAVs address a couple of key issues that need to be

applied for UAVs to perform their tasks successfully. First, their flight time needs to be

increased. In order to maintain simplicity and a lower cost, the flight time must be

increased by making the UAVs fixed-wing aircraft. A limitation that arises from using

fixed-wing aircraft is that they have a limitation on the airspeeds that they are allowed to

fly in order to maintain stable flight. Additionally, they have a turn rate constraint, as

they have to maintain a forward velocity. Second, the UAVs must have a high degree of

autonomy in which they perform missions without personnel intervention. In convoy

protection, they must not constrain the convoy from moving in a way it wishes to move.

Page 11: Path Planning UAV Sinus

2

Furthermore, in convoy protection and other surveillance missions it is desired to have

several UAVs in order to promote more complete coverage to identify possible threats.

The missions that this report will focus on are those involving surveillance. In

particular, convoy protection and SAR are of major importance to the US government

with heightened activities overseas and homeland security issues. Supply convoys that

are traveling through hostile territory need over-the-horizon surveillance in order to

watch out for what is ahead of them. For example, in February of 2003 a supply convoy

was ambushed in Iraq and taken hostage [15]. There is a chance, if they would have had

look-ahead surveillance, they would have known that they were driving towards hostiles.

During Coast Guard SAR missions, the most costly part of the mission, in terms of

money and lives, is the time that it takes to find a missing boat or persons in the water

[16]. If the searching could be enhanced by being able to explore a larger extent of land

during a given amount of time, the victims would be found much quicker and the chances

of being found would increase.

The way that UAVs come into play is that they could provide direct surveillance

for the convoy or fly abreast of a SAR helicopter to help perform surveillance. In order

to conduct such a routine, the UAVs must fly along a path that is continuously changing

and still maintain a distance relative to the convoy or helicopter. Furthermore, in order to

increase the effectiveness of the UAVs we may want multiple UAVs to work

collaboratively to perform the task. Therefore, they must be controlled a manner that

defines their path explicitly. The main objectives then become to define a path for the

UAVs to follow and to have them follow that path effectively.

The approaches in this thesis are general in that the point the UAVs would follow

can be anything from a person, to a truck, to a point 500 meters ahead of a convoy. The

general problem is that the UAVs have limitations in airspeed and turn rate capabilities,

while the point of interest (POI) may be able to move at slower speeds and have a tighter

turn rate capability, often being able to change directions from 0° to 360°. The motion of

the POI is unrestricted and not known in advance. Therefore real-time path generation is

needed in order to ensure that the UAVs track the POI.

Page 12: Path Planning UAV Sinus

3

1.2 Organization

To fulfill these demands, algorithms were developed for calculating the desired

path for UAVs. First, a navigation scheme will be presented that commands the UAV to

fly in a sinusoidal manner and by changing the amplitude of the sinusoid, all the while

maintaining a constant velocity and tracking the POI. The navigation scheme has two

modes for different velocity ratios between the UAV and the POI. Second, an enhanced

navigation scheme will be presented that eliminates the need for separate modes while

tracking the POI and utilizes velocity vector commands such that the path can be used for

a formation of UAVs.

After the presentation of these two tracking schemes, low-level control

enhancements to the existing autopilot [5] will be examined. In particular, turbulence

disturbance rejection will be the main focus of the enhancements to the autopilot. In light

of this, H∞ and H2 control will be developed and applied to the disturbance rejection

problem.

Page 13: Path Planning UAV Sinus

4

Chapter 2

Path Planning for a Single UAV

2.1 Introduction

As mentioned in the first chapter, the overall objective is to have UAVs perform a

surveillance routine while tracking a point of interest that is moving unpredictably, but at

a speed less than or equal to the speed of the UAVs. The UAVs are limited in their

forward velocity capabilities, only able to travel between a small range of velocities and

never flying at a standstill.

This chapter will generate a path that is effective for the goal at hand and suitable

for fixed-wing UAVs. The path planning algorithm will then be tested in simulation and

experimentation.

2.2 Path Planning Algorithm

The path planning algorithm that is presented in this chapter is one UAV tracking

a point of interest (POI). Obviously, the central goal of the algorithm will be to

maneuver the UAV to track the POI. It accomplishes this goal by changing modes when

the ratio of the UAV speed, VP, to that of the POI speed, VT, goes above a threshold ratio.

As a result, the behavior of the UAV is separated into two modes (loitering or

sinusoidal) depending on the velocity of the POI. If the velocity of the POI is much

slower than that of the UAV (i.e. velocity ratio is above the threshold), the UAV will be

Page 14: Path Planning UAV Sinus

5

in the loitering mode; otherwise, the UAV will go into the sinusoidal mode. The

sinusoidal curve in Figure 2.1 illustrates the desired path the UAV will follow using the

sinusoidal algorithm. The amplitude of the sinusoid, A, varies according to the ratio of

VP and VT. The POI is situated at the same x value as the UAV. In the figure the dashed

line is the projected path the POI is to follow, it is assumed that the path is straight.

D2 ;

D1=VT*T

A

vT

y1

x1

vP

xP

yP

Figure 2.1: Top view of path planner algorithm in sinusoidal mode

In Figure 2.1, D2 is the distance in the x direction the UAV will travel in one time

period, T, of the sinusoid. It will equal the distance, D1, that the POI will travel in the

same direction. Thus, D1 = VTT, where the period T is arbitrarily chosen. Using this fact,

the equation of a sinusoid can be transformed into an equation that describes the

sinusoidal path,

=

1

2sin

Dx

Ay PP

π. (2.1)

Here, xP and yP are the desired position of the UAV relative to the stationary x1-y1

coordinate system that updates to the position of the POI every period with the heading of

the POI in the x direction. Taking the time derivative yields

PP

P xD

xAy && ⋅

=

1

2cos'

π (2.2)

Page 15: Path Planning UAV Sinus

6

where 12' DAA π= . The magnitude of the UAV velocity, VP, is related to its x and y

components via

222PPP Vyx =+ && . (2.3)

Substituting Equation 2.2 into 2.3 results in

22

1

222 2cos' PP

PP Vx

Dx

Ax =⋅

+ && π

, (2.4)

which after some algebraic manipulation becomes

+

=

1

2 2cos'1

Dx

A

Vx

P

PP

π& . (2.5)

Equation 2.2 and 2.5 are used in the implementation of this algorithm to calculate

the desired path of the UAV. Proceeding further, an equation is now derived that will

relate the ratio of the UAV velocity and the POI velocity with the amplitude. First, note

that dtdxx PP =& , which allows us to express Equation 2.5 as the following integral,

P

D P

P

Tdx

Dx

AV

dt ∫∫

+= 2

01

22

0

2cos'1

1 π. (2.6)

Now, since

TdtT

=∫0 and TVDT 1= (2.7)

Equation 2.6 becomes

P

D P

PT

dxD

xA

VVD

+= 1

01

221 2cos'1

1 π. (2.8)

Let the velocity ratio be, Tp VV /=σ then

P

DP dx

Dx

AD ∫

+=

1

01

22

1

2cos'1

1 πσ . (2.9)

Page 16: Path Planning UAV Sinus

7

This equation is used in the implementation to determine the amplitude, A, of the

sinusoid, based on s . Equation 2.9 is a variation of a complete elliptic integral of the

second kind, which means it can be expressed as

))'((1 2

12AE −π

(2.10)

where E(…) is the aforementioned elliptic integral expressed in function form [1].

Figure 2.2 is a plot of s versus the ratio A/D1 based on Equation 2.9. The plot

shows that using this equation, the amplitude of the sinusoid will increase as the velocity

ratio gets larger. This makes sense because a larger s corresponds to an increasing VP or

a decreasing VT. In both cases the amplitude needs to be enlarged to slow the rate at

which the UAV follows the path of the POI.

Figure 2.2: Speed ratio, s , vs amplitude/distance, A/D1, ratio of path planning algorithm

(all D1 values overlap)

If the value of s is above a certain threshold value, hσ , the UAV will exit the

sinusoidal mode that generates the trajectory as discussed above and enter into the

loitering mode. The UAV will then loiter about the POI. The value of hσ is set to avoid

the large amplitude that would be caused by the high value of s . If the value of s

decreases below hσ , then the sinusoidal algorithm will continue.

Page 17: Path Planning UAV Sinus

8

In the loitering mode, the UAV enters into a circle or rose curve trajectory. The

option for using a circle or rose curve trajectory is up to the user based upon the desired

mission of the UAV. In the circle trajectory, the UAV circles about the POI and

essentially maintains a constant bank angle. The rose curve is beneficial because it will

allow a camera on the bottom of the UAV to face the ground for a greater amount of time

than when circling. The rose curve is created by giving the UAV waypoints in a line and

then after the UAV has gone through those points the line is rotated about a fixed center

located above the POI. Once the line is rotated, waypoints are given along the new line.

This pattern continues, until s decreases below hσ . A close-up for the rose curve is

shown in Figure 2.3.

Figure 2.3: Top view of path planning algorithm in the rose curve loitering mode

The reason the path has been developed in the lateral direction and not in the

longitudinal (up/down) direction is due to many factors. First, and foremost, the amount

of fuel consumed is a function of how much the altitude is increased. In a longitudinal

path the altitude would have to be increased often, thus expending more fuel. Second, the

velocity and altitude control of aircraft is more difficult than the lateral control. This

would not allow us to be as precise as we would like to be. Finally, although constant

surveillance on a straight line may be desirable, often it is more desirable to search a

wider path.

Page 18: Path Planning UAV Sinus

9

2.3 Wind Compensation

The ground velocity of the UAV is used for the path planning algorithm.

However, when wind is present the UAV’s ground velocity changes, while the true air

speed of the UAV is kept constant. Therefore, not only will the UAV have difficulty

following the sinusoidal path, but also the path-generation algorithm will also generate

paths with undesirable features. Fortunately, the UAV has the capability to estimate the

wind velocity, which can be used by the path-generation algorithm. This new path is

offset at a ratio of the wind velocity vector; therefore adding or subtracting to the distance

of the next waypoint for the UAV to go to. Additionally, a hysteresis was added to

eliminate frequent switching between the loitering and sinusoidal modes that is caused by

the fluctuation of the UAV’s ground speed.

2.4 Simulation Implementation and Results

The simulation and experimental platform used for testing these algorithms was

the Piccolo system built by Cloud Cap Technology [5]. The Piccolo is a self-contained

avionics and autopilot system for small aircraft (Figure 2.4). One feature of this flight

system is that it can be used in a hardware-in-the-loop simulation. The term hardware-in-

the-loop (HIL) simulation refers to a simulation in which many of the hardware

components are included in the simulation platform. Unlike a simulation run only on

computers, HIL simulation uses the wireless communication and embedded computers

that are actually used in the actual experiment. Here, the Piccolo avionics may be hooked

up to a computer that simulates the aircraft dynamics and sensors. The Piccolo avionics

communicates with a ground station, shown in Figure 2.5, which sends high-level

commands to the avionics. The radio link between the Piccolo avionics and the ground

station is a 900 MHz frequency hopping radio. The avionics only receives commands

from the ground station every 1 Hz. A single ground station is able to communicate with

multiple Piccolo avionics boxes. For visualization purposes the simulated aircraft and the

ground vehicle simulation are sent to a visualization computer. A general schematic of

the HIL simulation setup is shown in Figure 2.6. The schematic is a general schematic

Page 19: Path Planning UAV Sinus

10

that will be applicable when there are multiple UAVs to be simulated and controlled in a

formation, which will be addressed in the next chapter.

Figure 2.4: Piccolo miniature Figure 2.5: Piccolo ground station

avionics system

Figure 2.6: Hardware-in-the-loop (HIL) simulation schematic with 3 aircraft

Total System Visualization

Ground Vehicle Simulation Trajectory Generation

Formation Control

UAV 1 Sim. UAV 2 Sim. UAV 3 Sim.

Ground Station

Ground Vehicle Data

UAV Data

Piccolo avionics

Page 20: Path Planning UAV Sinus

11

We have successfully simulated the path planning algorithm using a simulation

platform built on the computer connected to the ground station. A ground vehicle

simulation was developed in order to aid in the simulation. Within the graphical user

interface that runs the program, we can define the POI as any offset distance and offset

angle with respect to the ground vehicle, as shown in Figure 2.7.

Figure 2.7: Point of interest (POI) defined in terms of the ground vehicle by an offset

distance, L, and offset angle, θ

The ground vehicle simulation is built using a simple model. The discrete time

equations for the position of the ground vehicle are given by Equations 2.11 and 2.12:

xLat(k+1) = xLat(k)+ vN? T (2.11)

xLong(k+1) = xLong(k) + vE? T (2.12)

where the position of the ground vehicle model is reported in degrees of latitude, xLat, and

longitude, xLong. The velocity magnitude in the north direction is vN and the velocity in the

east direction is vE. Since the algorithm is run once every second, an update of the

ground vehicle model’s position occurs at 1Hz, and so the ? T in Equations 2.11 and 2.12

is set to one.

Page 21: Path Planning UAV Sinus

12

The velocity vector of the ground vehicle is determined through the heading and

the speed. Equations 2.13 and 2.14 calculate the velocity in terms of radius of the earth

and in units of degrees.

πψ 180)cos(

⋅=Lat

TN r

Vv (2.13)

πψ 180)sin(

⋅=Long

TE r

Vv (2.14)

where rLat and rLon are the radius of the earth in latitude and longitude direction,

respectively; VT is the magnitude of the ground vehicle’s velocity vector as in the

preceding section and ? is the heading.

The ground vehicle’s position and velocity are used with the path planning

algorithm in order for a simulated UAV to follow the POI defined with respect to the

simulated ground vehicle before implementation with the actual aircraft and ground

vehicle. The simulated aircraft was previously developed by CloudCap Technology [5].

Simulations were conducted to assist in the development of the path planning

strategies and to confirm that the software would work with an actual aircraft. For the

following simulations, the POI is defined directly on top of the ground vehicle, unless

otherwise noted. The speed of the UAV is held constant at approximately 20-23 m/s

throughout all of the simulations and experiments. The results of a simulation test with

the ground vehicle heading south at a constant 10 m/s are shown in Figure 2.8. The value

of s is approximately 2, which is lower than the threshold value of hs = 3; thus, the path

is a sine wave. There is no wind in this simulation.

The next step in the simulation process is to test the wind compensation

algorithm. The simulated UAV estimates the simulated wind velocity, which is used in

the wind compensation algorithm. The wind is simulated at 10 m/s coming from the

south. First, a simulation was conducted without any wind compensation in the path

planning algorithm. The resulting path is shown in Figure 2.9. The ground vehicle is

traveling at 10 m/s to the north and then turns and heads at 10 m/s to the east. The UAV

has difficulty following the sine wave with tail wind; the UAV goes too far and then has

Page 22: Path Planning UAV Sinus

13

to cut back. When the UAV has a crosswind it stays too far away from the ground

vehicle (to the side).

-122.34 -122.335 -122.33 -122.325 -122.32 -122.315 -122.31

37.74

37.745

37.75

37.755

37.76

Longitude

Latitude

Car PathDesired PathPlane Path

Figure 2.8: Simulation of UAV and ground vehicle with no wind and the ground vehicle

traveling south at a constant velocity

-122.3 -122.29 -122.28 -122.27 -122.26 -122.25 -122.24

37.59

37.595

37.6

37.605

37.61

37.615

37.62

37.625

37.63

37.635

Longitude

Latitude

Car PathPlane Path

Figure 2.9: Simulation with no wind compensation, 10 m/s south wind, and constant

ground vehicle speed

Page 23: Path Planning UAV Sinus

14

Next, a simulation is shown with the wind compensation added (Figure 2.10).

The wind and vehicle conditions are the same as the previous experiment. Notice that the

sine wave paths are much better and the path is centered over the ground vehicle. In the

simulations and algorithms that are derived in this section, constant wind is the only

external disturbance included; gusts have not yet been considered.

-122.39 -122.385 -122.38 -122.375 -122.37 -122.365 -122.36 -122.355 -122.35 -122.345 -122.34

37.535

37.54

37.545

37.55

37.555

37.56

37.565

37.57

Longitude

Latitude

Car PathPlane Path

Figure 2.10: Simulation with wind compensation, 10 m/s south wind, and constant

ground vehicle speed

-122.31 -122.305 -122.3 -122.295 -122.29 -122.285 -122.2837.735

37.74

37.745

37.75

37.755

37.76

Longitude

Latitude

Car PathDesired PathPlane Path

Figure 2.11: Simulation with no wind and changing speed in the ground vehicle (switch

from sinusoidal to loitering mode)

Ground vehicle stops: Mode switched

Page 24: Path Planning UAV Sinus

15

Figure 2.11 demonstrates the viability of the loitering and sinusoidal modes and

the switch between the two modes. The ground vehicle is heading approximately north at

8 m/s and then comes to a halt. At that time, the UAV enters into a loitering mode and

starts circling the ground vehicle. After a couple of seconds, the offset distance is slowly

increased so that the UAV will loiter over a region ahead of the ground vehicle. (This

can be seen by the circles that continue after the car path ends.)

As demonstrated above, reassuring simulation results were attained, which

increased the confidence for an experiment to verify the path planning strategy.

2.5 Experimental Results

A UAV furnished by Advanced Ceramics Research (ACR) was outfitted with

Cloud Cap Technology’s Piccolo system for low-level control. The path planning

algorithm was incorporated into the laptop connected to the ground station software, and

the ground station was loaded in the bed of a truck. Figure 2.12 shows the experimental

setup with three aircraft and the trajectory generation running on the ground station

aboard the truck. Notice the similarity between this setup and the HIL simulation shown

in Figure 2.6. The aircraft replace the laptop, and the truck replaces its simulation;

otherwise everything else is the same.

Figure 2.12: Diagram of experimental setup with 3 aircraft

Trajectory Generation Formation Control

UAV 1

Ground Station

UAV 3

UAV 2

Page 25: Path Planning UAV Sinus

16

The truck was driven at speeds varying from 0 to 45 mph throughout the test. At

all times the UAV followed the motions of the truck by traveling either in a sine wave

trajectory or loitering. There was no angular offset for the test. The POI was set to be

40m in front of the truck at all times and then moved directly above the truck when it was

in loitering mode. There were low wind conditions for the day of the test.

Figure 2.13 shows the entire data from the experiment. The truck primarily made

90° turns, per constraint of the desolate desert highways in Tucson, Arizona. The truck

first began to travel towards the west with a high value of s (i.e. slow moving truck);

therefore the UAV was in loitering mode. The truck then returned to the starting point

and then began to travel south. At this point the s value is approximately 2. Following

this jaunt, the truck headed toward the east with the same sigma value. Two miles later,

the truck made a U-turn and reversed its route to return to the starting point. Throughout

the return trip the s value was roughly 2/3. The long stretch throughout most of the plot

had a low enough s value for the UAV to stay in sinusoidal mode.

-109.76 -109.75 -109.74 -109.73 -109.72 -109.71 -109.7 -109.69 -109.6832.08

32.09

32.1

32.11

32.12

32.13

32.14

Longitude

Latitude

Car PathDesired PathPlane Path

Figure 2.13: Data from the entire experiment, with the UAV following a truck. The

truck started on the west side of the plot and drove east at varying speeds, then turned

back and retraced its path.

Page 26: Path Planning UAV Sinus

17

Figure 2.14 exhibits a close-up of the loitering mode. Notice the path is circular

instead of a rose curve. This was the loitering pattern chosen for the day of the

experiment. Figure 2.15 separates the long east to west stretch of the experiment from

the rest of the experimental data. The experimental results shown here verify the

simulation results.

-109.7605 -109.76 -109.7595 -109.759 -109.7585 -109.758 -109.7575 -109.757

32.1145

32.115

32.1155

32.116

32.1165

32.117

Longitude

Latitude

Car PathPlane Path

Figure 2.14: Close up of experimental data highlighting loitering mode

-109.75 -109.74 -109.73 -109.72 -109.71 -109.7 -109.69

32.085

32.09

32.095

32.1

32.105

32.11

32.115

32.12

32.125

32.13

32.135

Longitude

Latitude

Car PathDesired PathPlane Path

Figure 2.15: Close up of experimental data highlighting sinusoidal mode. The truck was

traveling from the east to the west in the plot.

Page 27: Path Planning UAV Sinus

18

The real time video feed provided situational awareness coverage at nearly all

times during the test. The picture in Figure 2.16 was captured from the video footage

provided from the camera onboard the aircraft. The picture displays the aircraft’s view as

it passes over the truck. The points at which the UAV path and truck path cross are

essentially the zero-point of the UAV’s sine wave trajectory.

Figure 2.16: Picture of video taken from a camera on the bottom of the UAV.

Page 28: Path Planning UAV Sinus

19

Chapter 3

Orbital Trajectory Specification for Multiple

UAVs

3.1 Introduction

The previous chapter featured a single UAV tracking a point of interest (POI)

while flying in a sinusoidal path. Although this approach worked well, the sinusoidal

path was only applicable to certain velocities of the POI. Under which, the UAV had to

change its desired trajectory and switch into a different mode for slow POI speeds. The

previous approach also did not feature feedback of the actual UAV position in order to

control where it should fly.

This chapter expands upon the previous approach on several fronts. First, the

need for mode switching has been eliminated in this new approach, the

sinusoidal/loitering path generation is replaced by an orbit trajectory generation method.

Second, we advance the methodology by developing an algorithm that can be tuned for

the flight parameters of a given aircraft. Third, the trajectory is able to be used to in

conjunction with a coordinated control algorithm that allows multiple aircraft to track the

POI. Collision avoidance routines have been implemented such that multiple UAVs can

fly in a pattern to perform convoy protection and surveillance while maintaining safe,

collision-free flight.

Page 29: Path Planning UAV Sinus

20

The outline of this section is as follows. In section 3.2, the orbit trajectory is

formulated along with establishing some of its key properties. The control strategy that is

used to track this trajectory is also discussed. In section 3.3, a brief overview of the

formation control will be presented. Section 3.4 includes results of the hardware-in-the-

loop (HIL) simulations. Section 3.5 highlights the results from a recent two aircraft

demonstration.

3.2 Orbital Trajectory Theory

3.2.1 Definition

In order to generate a trajectory for the UAVs to follow, a scheme is developed

such that the UAVs can use the same method of developing a trajectory for all possible

velocities of the POI. The trajectory in this new approach is for any number of UAVs to

follow. If the trajectory is for a group of UAVs, the individual UAVs follow the group

trajectory using the formation controller, which is summarized in the next section. In this

section we can assume that the trajectory and control that is developed here could be

given to one aircraft or to multiple aircraft through the formation control.

The trajectory is based on a whole family of possible orbital trajectories. Orbital

trajectories are defined as trajectories that use a point of interest to define their location

and orientation. The trajectory chosen for our application is referred to as the lemniscate

trajectory. It was chosen based on the desirable properties that it had, such as gentle

curves, continuous derivatives, and several other nice mathematical properties. The

trajectory is generated in the POI coordinate frame that moves with the POI and has its

heading always aligned with the y-direction. Figure 3.1 illustrates the lemniscate

trajectory in (a) POI coordinates and (b) ground fixed frame coordinates. As the ratio of

POI speed to aircraft speed varies from zero to one, the path traced by the aircraft

changes smoothly from a figure-8 to a periodic curve to a straight line. It will be shown

later in this section how the parameters are chosen for different relative speeds of the POI

and the aircraft.

Page 30: Path Planning UAV Sinus

21

-500 -400 -300 -200 -100 0 100 200 300 400 500

-400

-300

-200

-100

0

100

200

300

400

x (m)

y (m )

rTrLEM

(a)

-500 -400 -300 -200 -100 0 100 200 300 400 500

0

100

200

300

400

500

600

700

800

y (m )

x (m)

rTrLEM

(b)

Figure 3.1: (a) Lemniscate trajectory in POI coordinates

(b) Lemniscate trajectory in fixed reference frame coordinates, position of the POI is

shown by the dashed line

Orbital trajectories are defined in terms of a reference frame that moves with the

POI. The lemniscate trajectory is defined by the following equation

Page 31: Path Planning UAV Sinus

22

)cos( θpAr = (3.1)

where r and θ are cylindrical coordinates in the POI coordinate frame. θ is the angle

from the local x-axis. p and A are the variables to be chosen based on desired trajectory

properties. In particular, A is the amplitude of the trajectory

The position of the lemniscate trajectory is given by

( )

=

=

θθ

θθθ

sincos

)cos(sincos 2/1

LEM pArr

r (3.2)

where BLEMLEM )(: rr = is the position in the POI coordinate frame. The primary

coordinate frames used in this section are (1) the POI coordinate frame, B, which has the

y-axis aligned in the direction that the POI is heading, the x-axis to the right, and the z-

axis up (2) the ground fixed frame, A, always aligned with the x and y axis of the POI.

Note that the derivations in this section assume that the two frames are aligned. Only

when the final desired velocity vector is calculated for the formation controller will there

be a conversion to a universal coordinate frame. Additionally, the coordinate frames are

inertial frames as it is assumed that the POI does not have any acceleration.

With these coordinate frames the total velocity along the trajectory in terms of the

POI coordinate frame, B, will become

BLEMB

BTA

BLEMA

A )()()(: vvvv +== (3.3)

The velocity along the trajectory in the ground fixed frame may be expanded by,

+

=

=

Ty

x

Ty

x

Vvv

Vvv 0

:Av (3.4)

where VT is the velocity of the POI.

3.2.2 Parameterization

Now that we have chosen the governing shape of the UAV’s trajectory, the exact

values of the trajectory parameters are developed. The first constraint that will govern

choosing the parameters of the trajectory is the maximum turn rate for a fixed-wing

Page 32: Path Planning UAV Sinus

23

aircraft to maintain relatively stable flight. In fact, the UAVs that were used in the

experiments had a maximum turn rate of 10 deg/sec, but due to the implementation with a

formation controller that has additional demands, the maximum turn rate was set to 7

deg/sec. The turn rate, Ψ& , was calculated from the lemniscate trajectory by finding the

acceleration that the UAV would have at each point on the lemniscate if perfect tracking

was maintained. The turn rate then becomes the magnitude of the acceleration over the

speed of the UAV (it is assumed that the UAV is in coordinated flight and the speed is

constant).

PTP VApVV /max),,,(max Aaθθ

=Ψ& (3.5)

where VP is the velocity of the aircraft and BLEMA

A )(: aa = .

Given this constraint, the maximum turn rate varies for a given trajectory based

on p, A, VP, and VT. The maximum turn rate was found through a sequence of steps that

will be outlined here. We can calculate the velocity by inserting Equation 3.2 into

Equation 3.3, which yields

( )

+

=

θθ

θsincos

)cos(0 2/1

A pAdtd

VT

v . (3.6)

Carrying out the differentiation gives,

( )

−−−−

+

= −

θθθθθθθθ

θθc)(cs)(ss)(cc)(s

)(c0

2

22/1

21

A pppp

pApV p

p

T

&v . (3.7)

The velocity, vA, can be found by Equation 3.7 if we had θ& . Since we are given

the UAV velocity, VP, and the POI velocity, VT, we can also calculate the trajectory

velocity, vA, through another method. First, we define the velocity ratio in the POI

coordinate frame as

x

Ty

v

Vvm

−=: . (3.8)

Page 33: Path Planning UAV Sinus

24

Next, we shall rearrange Equation 3.8 as m

Vvv Ty

x

−= and combine it with the

aircraft velocity squared 222yxP vvV += . We will also define the following notation, s :=

VP / VT, to give the final result in a simpler form. Using the above relations, we can find

vy of Equation 3.4 to be

),(:1

1)1(12

22

σσ

mhVm

mmVv TTy

±=

+−+±

= (3.9)

where h- is used when vx < 0 and h+ is used when vx > 0.

With vy available, we can find also define vx using Equation 3.8, and insert them

back into Equation 3.6, which yields

( ) ( )

−=

−+

=

±

±−±

),(

1),(1

1),(0 1

A

σ

σσmhV

mhmVm

mhVV

T

T

TT

v (3.10)

where m can be calculated by using the second term of Equation 3.7:

θθθθ

θθθθ

s)(cc)(s

c)(cs)(s2

2

pp

ppm

v

Vv

p

p

x

Ty

−−

−−==

− (3.11)

Combining Equation 3.7 and 3.10 and solving for θ& gives us the angular velocity

around the trajectory. With θ& at hand, the trajectory’s acceleration can be solved by

calculating

θ

θd

d AA

va &= (3.12)

Once the acceleration is found, the turn rate is computed using the assumption

that the aircraft acceleration only comes from centripetal acceleration (forward velocity is

constant).

AA va Ψ= & (3.13)

Page 34: Path Planning UAV Sinus

25

As mentioned in Equation 3.5, we calculate the maximum turn rate by finding the

magnitude of the trajectory’s acceleration over all values of θ and divide by the UAV’s

velocity. It is evident that the turn rate would be different for every value of VT and VP.

The turn rate will be a decisive part of choosing the parameters p and A, but we

would also like the UAVs to travel over the POI every so often in order to fulfill the

mission of tracking the POI and performing surveillance. Therefore, our next

specification will be to make the orbit parameters based on the return time. Return time

is defined as the time between each pass over the POI. The return time, T, is derived by

∫∫ == dsdsdt

dtT (3.14)

where s is the surface parameter. The time derivative of s is

LEMBLEMBLEM :)( vv

r===

dtd

dtds

. (3.15)

We can find ds by taking the computing the derivative of LEMr with respect to θ.

22

222

LEM2LEM

2 )()(c)(s)(t4

)()( θθθθθθ

dpppp

Add

ddds

+===

rr (3.16)

θθθθ dpppAds p )(c)(s)(t4

2

+=⇒ (3.17)

Combining Equations 3.14, 3.15, and 3.17 produces

∫∫=

=+== p dpppAds

dsdt

T p2 2

0 4LEM

)(c)(s)(t1

2πθ

θθθθθ

v (3.18)

Equation 3.18 is able to be numerically integrated using Equations 3.8, 3.9, and 3.10 to

assist in the solution of LEMv . With both the maximum turn rate and return time

available, p and A were chosen such that there is a different curve for each value VP and

VT that satisfies a maximum return time and a minimum turn rate. The algorithm to

choose p and A is shown in Figure 3.2.

Page 35: Path Planning UAV Sinus

26

Figure 3.2: Trajectory parameter assignment algorithm

A sample of the resulting orbital trajectories that were chosen for our application

are shown in Figure 3.3. The plots are shown in the POI coordinate frame. VT is varied

while VP is held constant at 20 m/s. It is evident that the amplitude decreases as the speed

of the POI increases. Also, p increases while the VT increases, which is apparent through

the narrowing of the trajectory. In Figures 3.4 and 3.5, the values for p and A are shown

versus all possible values of VT and VP for the different aircraft that may be flown (our

application works with three aircraft, having velocity ranges of 8-13 m/s, 17-24 m/s, and

21-26 m/s).

-500 -400 -300 -200 -100 0 100 200 300 400 500

-300

-200

-100

0

100

200

300

x (m)

y (m )

VT = 0 m/s

VT = 5 m/s

VT = 10 m/s

VT = 15 m/s

VT = 20 m/s

Figure 3.3: Trajectories in the POI coordinate frame with the aircraft velocity held

constant at VP = 20 m/s and the POI velocity, VT, is varied from 0 to 20 m/s

Trajectory Parameter Algorithm (1) Choose A very small (2) Calculate p to minimize the maximum turn rate over the entire orbit

- if p does not meet the maximum turn rate restriction, go to step 1 and increase A - if p meets the turn rate criteria, then make sure we meet the return time restriction

o if we do not meet the return time restrictions, then go to step 1 and increase A

(3) Done

Page 36: Path Planning UAV Sinus

27

Figure 3.4: Values of the trajectory parameter, p, versus the aircraft velocity, VP, and the

POI velocity, VT

Figure 3.5: Values of the trajectory parameter, A, versus the aircraft velocity, VP, and the

POI velocity, VT

Page 37: Path Planning UAV Sinus

28

3.2.3 Orbit Control

The stable control law that is developed for the group of UAVs to follow the

trajectory is defined in terms of the trajectory’s tangent line. Given the position, the unit

tangent vector, tLEM, is calculated in the POI coordinate frame as

θ

θ

dd

dd

LEM

LEM

LEM r

r

t = (3.19)

where the x and y components of the derivative of the position vector are given by

Equations 3.20 and 3.21

( )

−−=

θθθθθ

θs)(c

2c)(s

2)c()( 2/1

LEM pp

pppA

dd xr

(3.20)

( )

−−=

θθθθθ

θc)(c

2s)(s

2)c()( 2/1

LEM pp

pppA

d

d yr (3.21)

The two components can be collected and then divided by the magnitude to result in

( )

−−−−

+==

θθθθθθθθ

θθθ

θ

θ

θc)(cs)(ss)(cc)(s

)(c)(s)(t

)c(2

2

4

2/121

LEM

LEM

LEM 2 pppp

ppp

pp

dd

dd

p

p

pr

r

t . (3.22)

The control laws are defined using a vector between the aircraft’s position in the

POI coordinate frame, BPP )(: rr = and the position on the trajectory that is normal to this

rP. The normal position is found by setting the dot product of the aircraft’s position and

the tangent vector equal to zero. The trajectory will often have several positions that are

normal to the aircraft. The method of choosing which position to use is chosen by a

routine that predicts which quadrant in the POI coordinate frame that the aircraft should

be in or be heading towards, combined with choosing the position closest to the origin if

two solutions are found in the predicted quadrant. This position is called pL and the

normal vector between rP and pL is n as shown in Figure 3.6.

Page 38: Path Planning UAV Sinus

29

Figure 3.6: Control law development for a single UAV following an orbit trajectory

Once pL is found, the tangent vector at pL is determined, tLEM(pL), and its angle is

calculated, ζ. Also, the control angle,θc, is computed using

)(tan 1 ntc K−=θ (3.23)

where Kt is a controller gain. Kt can also be intuitively looked upon as the inverse of the

distance ahead of the pL that you would like to have the UAV head towards, L. Based on

simulations, L was chosen to be 125m, or Kt = 0.008. One reason why we chose such a

large L is due to the delay that we experience in the controller. We only receive position

data from the aircraft every 1 second.

The formation controller is given the desired velocity vector of the UAV in a

global coordinate frame. The desired velocity vector, assuming constant speed of the

UAV is

++

=)sin()cos(

:ζθζθ

c

cPd Vv (3.24)

pL

L = Kt -1

rP

θc ζ

n

Page 39: Path Planning UAV Sinus

30

3.3 Formation Control

The formation controller that is used was developed by Spry [12], and is a general

approach to multiple vehicle formations. The formation controller allows for control in

terms of relative and absolute motion, so it fits in perfectly with out application. The

formation of UAVs can be specified to be at a desired location with a specific speed

(absolute motion), and the individual UAVs can hold a given formation with desired

distances between them (relative motion). The controller also has inherent collision

avoidance, as by maintaining the formation it keeps a specified distance between the

UAVs. Finally, the orbit trajectory control developed above is able to command the

desired velocity vector as in Equation 3.24.

The formation is described in terms of three coordinates. The first coordinate is a

location (L) of a formation reference point (FRP). The second coordinate defines the

orientation (O) of the formation reference frame (FRF), which is specified given a

particular formation. The third coordinate defines the particular formation shape (S)

configuration relative to the FRF. The FRP is a point that remains rigidly attached to the

formation during any rigid displacement. The FRP is what is used in to follow the orbit

trajectory. Usually, two aircraft (or virtual aircraft) define the FRP and the FRF (not

necessarily the same aircraft). For our application, the FRF is specified to align the

UAVs in a straight line perpendicular to the heading of the POI. This is for maximizing

the coverage area, and could be changed for other goals that one could have for the

formation of UAVs. The concept of the orbit working in conjunction with the formation

controller is shown in Figure 3.7.

Figure 3.7: Illustration of orbit trajectory and the formation

POI coordinate frame, origin fixed to POI

Orbit shape and amplitude vary with

POI speed

FRP tracks orbit

Page 40: Path Planning UAV Sinus

31

3.4 Simulation Results

The orbital trajectory and formation controller were implemented on a laptop that

was connected to the ground station. The ground vehicle simulation was included as in

section 2.4. Simulations were conducted to assure that the algorithms would work

successfully once they are employed on the actual aircraft.

Figure 3.8 features a test with three UAVs following a ground vehicle. The

ground vehicle started off at a standstill and the velocity was slowly increased to the

speed of the UAV (20 m/s). The ground vehicle headed straight north during the

simulation. Notice that the UAVs orbited the ground vehicle in a figure-8 pattern and

then as the speed increased the orbit turned into a periodic wave that eventually emulated

a sine wave. Finally, as the ground vehicle’s speed reached that of the UAVs, they flew

in a straight path. In addition, the amplitude of the trajectory slowly decreased

throughout the simulation.

-6000 -4000 -2000 0 2000 4000 6000

0

1000

2000

3000

4000

5000

6000

7000

8000

9000

10000

x (m)

y (m )

UAV 0UAV 1UAV 2Grouind Vehicle

Figure 3.8: Simulation with 3 UAVs tracking a ground vehicle. The ground vehicle’s

velocity, VT, increases from 0 to 20 m/s

Page 41: Path Planning UAV Sinus

32

Another simulation is shown in Figure 3.9, which has the ground vehicle start out

at a standstill at position (0,0) and then increase its velocity to 12 m/s. The ground

vehicle then makes several right-hand turns followed by a left-hand turn. Notice, that

every time the ground vehicle makes a turn, the UAVs slowly realign themselves so that

they are perpendicular to the ground vehicle’s heading.

-500 0 500 1000 1500 2000 2500 3000 3500 4000

-2000

-1500

-1000

-500

0

500

1000

1500

x (m)

y (m )

UAV 0UAV 1UAV 2Ground Vehicle

Figure 3.9: Simulation with 3 UAVs tracking a ground vehicle. The ground vehicle’s

velocity, VT, is 12 m/s as it turns in many directions

3.5 Experimental Results

An experiment was conducted using the same system as in section 2.5. The

UAVs that were used in the experiment were Rascal UAVs (see Figure 3.10), which

replaced the simulated UAVs that were used in the HIL simulation in the previous

section. Two UAVs were flown in formation following a truck driving along the road.

The truck drove out of a parking lot onto a road. The truck then went north for about 3

km at 10 m/s and turned around and heading back down the road heading south.

Page 42: Path Planning UAV Sinus

33

Throughout the experiment the two UAVs followed the truck using the orbit trajectory

and formation control. A picture of the truck and UAV paths is shown in Figure 3.11.

Figure 3.10: Picture of Rascal experimental UAV platform

Figure 3.11: Top view of experiment with UAV and ground vehicle paths overlaid on

map of testing site

UAV 1 UAV 2 Truck

(Approx. 4km x 4km)

Truck: 10 m/s Aircraft: 20 m/s

Approx. Speeds:

Page 43: Path Planning UAV Sinus

34

Figure 3.12: Ground coverage plot from the UAV cameras

The camera coverage of the UAVs was also examined and is shown in Figure

3.12. The data is from the truck heading north. One of the goals of the experiment was

to perform surveillance around the truck’s path. Here, it shows that there is almost

complete coverage of the area around the road. Using more UAVs would allow for a

wider coverage area. Also, note that if the UAVs would have been flown in a formation

such that they were lined parallel to the direction of the heading of the truck there would

be a different coverage shape. The formation would allow for coverage in front of and

behind the POI.

Formation flight with three UAVs has been conducted by our group. Due to

hardware difficulties, three aircraft were never flown using the algorithm presented in

this chapter. A picture of the three UAVs is shown in Figure 3.13.

Page 44: Path Planning UAV Sinus

35

Figure 3.13: Picture of three UAVs flying in formation

Page 45: Path Planning UAV Sinus

36

Chapter 4

Disturbance Rejection Control

4.1 Introduction

Now that we have defined a subset of paths that a UAV could be commanded to

follow, we need to make sure that the lateral control of the UAVs is sufficient to keep the

UAVs following the paths. Due to the turbulence that is faced in many flying conditions

for fixed-wing aircraft UAVs, there is a need to implement a disturbance rejection

controller with the current autopilot system. The turbulence perturbs the UAV off of the

desired path, and prevents closer formation flight and optimal usage of cameras mounted

on the bottom of the UAVs.

Disturbance rejection has been a topic of control basically since its inception.

This thesis is not meant as an exhaustive search of disturbance rejection controllers,

although it is nice to mention a few for the reader who is interested in developing

controllers of their own. Bode had many groundbreaking results in the 1940s [3], and

advances have been made ever since. Many SISO disturbance rejection controllers were

developed in the 1960s and 70s, in particular, LQG and the Weiner-Hopf control

methodology [19]. In the 1980s, H8 and H2 control became very popular with the results

of Doyle and many others [6, 7, 11].

There are many limitations in making a good disturbance rejection controller.

First, sensors that are used for control (gyros, accelerometers, etc.) often have high

frequency noise (and low frequency bias) that inhibits their ability to measure high

Page 46: Path Planning UAV Sinus

37

frequency disturbances. Due to the structure of feedback systems, in order to reject

disturbances at a given frequency, we are not allowed to reject sensor noise at that

frequency. This concept will be addressed later in this chapter. Additionally, we have

limitations in our actuators such as bandwidth and saturation that limit the ability to reject

some disturbances. On top of all of these limitations, we must be able to follow our

command input to achieve good tracking. The goal of the work in this chapter will be to

restrict the effect of turbulence while still achieve good tracking of a desired turn rate

that, in turn, yields good tracking of a curve or line.

This chapter is laid out by opening up with a brief rundown on aircraft dynamics.

Subsequently, an explanation of the simulation environment that will be used for the

controller development will be given. After explaining the simulation environment, an

overview will be given of the current lateral autopilot that is implemented in the avionics

system. Then, simulation results for the current autopilot will be shown. Next, small

enhancements to the autopilot assisting in disturbance rejection will be discussed and

results will be shown. Following discussion of these small enhancements, more drastic

changes such as H2 and H8 control will be the talked about: first, in theory; second, in

implementation; and third, in simulation and results. During the section on H8 control,

actuator models, the wind model, and sensor models will be explained in detail.

4.2 Overview of Aircraft Dynamics

This section is not meant to give a complete explanation of aircraft dynamics, but

rather is a primer intended to enable the reader to be able to understand the nomenclature

and general dynamics of an aircraft. Most of the information in this chapter comes from

textbooks by Etkin [9] and Bryson [4].

The standard dynamical model of an aircraft is composed of twelve states:

`]`,`,,,,,,,,,,[ zyxrqpwvu ψθφ where

),,( framebody in elocity aircraft v],,[ bbb zyxwvu = (see Figure 4.1)

),,( framebody in locity angular veaircraft ],,[ bbb zyxrqp =

Page 47: Path Planning UAV Sinus

38

=],,[ ψθφ Euler angles of a 3-2-1 transformation between body frame and earth-

fixed frame = roll, pitch, yaw

=`]`,`,[ zyx position of the aircraft with respect to the earth-fixed frame

The nonlinear dynamical equations for an aircraft are [4]:

( )( )( ) εφθ

φθεθ

sTccgmZuqvpwmscgmYwpurvm

cTsgmXvrwqum

⋅−⋅⋅⋅+=⋅−⋅+⋅⋅⋅⋅+=⋅−⋅+⋅

⋅+⋅⋅−=⋅−⋅+⋅

&&&

(4.1)

( )( ) ( )

( ) NrqIqpIIpIrI

MprIrpIIqI

LqpIrqIIrIpI

xzxyxzz

xzzxy

xzyzxzx

=⋅⋅−⋅⋅−+⋅+⋅

=−⋅+⋅⋅−+⋅

=⋅⋅+⋅⋅−+⋅+⋅

&&

&

&&22 (4.2)

rcc

qcs

rsqc

rtcqtsp

⋅+⋅=

⋅−⋅=

⋅⋅+⋅⋅+=

θφ

θφ

ψ

φφθ

θφθφφ

&

&

&

(4.3)

u,X

w,Z

v,Y

r,N

p,L

q,M

zb

xb

yb

Figure 4.1: Aircraft velocities, forces, and moments in body-axes (courtesy of Eric Frew)

Page 48: Path Planning UAV Sinus

39

wccvcsusz

wcssscvccsssuscywsscscvsccssuccx

⋅⋅+⋅⋅+⋅−=⋅⋅−⋅⋅+⋅⋅+⋅⋅+⋅⋅=⋅⋅+⋅⋅+⋅⋅−⋅⋅+⋅⋅=

θφθφθψφψθφψφψθφψθψφψθφψφψθφψθ

`)()(`)()(`

&&&

(4.4)

where m = mass of aircraft, Iii are the moments of inertia, =],,[ ZYX aerodynamic forces

on the aircraft in body axes coordinates, and =],,[ NML aerodynamic moments on the

aircraft in body axes coordinates, T is the thrust, and ε is the angle of thrust with the xb-

axis.

The aerodynamic moments and forces are functions of all of the states and all of

the control inputs, for instance ( )trearqpwvuXX δδδδ ,,,,,,,,,= , where =aδ aileron

deflection, =eδ elevator deflection, =rδ rudder deflection, and =tδ throttle deflection.

The aircraft models are sometimes derived in terms of the aircraft velocity, V, and

its associated polar angles: the angle of attack, α, and the angle of sideslip, β. The

relationships between the above states and these alternative states are:

222 wvuV ++= (4.5)

( )221tan vuw += −α (4.6)

( )uv1tan−=β (4.7)

If the aircraft is assumed to be close to an equilibrium, or trim, condition then the

equations of motion can be linearized and the states can be broken into their lateral and

longitudinal states. The lateral states then become v, p, r, φ, ψ, and y` and the control

inputs are aδ and rδ . The longitudinal states are u, w, q, θ, x`, z` and the control inputs

are eδ and tδ . The longitudinal states will be assumed to be relatively constant and

maintained by the current autopilot. The lateral states are the path planning states with

the aileron and rudder as the controls.

Throughout this section the aircraft that will be used is the Aerosonde UAV [14].

The linear model given that the aircraft is flying at h = altitude = 490 meters, V = aircraft

velocity = 24 m/s, φ = roll angle = 0° is:

Page 49: Path Planning UAV Sinus

40

−−−−

+

−−−

−−−−

−−

r

a

w

w

w

pprrvv

prv

δδ

φφ 0035.2158.4

09.221.11638.332.1

006.010005.171.269.0007.1092.2125.481.996.2343.165.0

&&&&

(4.8)

The sensors that are used for lateral motion observe the roll rate, p, the yaw rate,

r, and the lateral acceleration, ay = v& . The roll angle, φ , is also estimated using an

integration scheme on the roll rate sensor.

4.3 Simulation Environment

The simulation environment that will be used for low-level controller

development is an aircraft dynamics simulator built by Unmanned Dynamics called

AeroSim [14]. AeroSim is a blockset for MATLAB’s Simulink, so controller

development will be eased by the ability to use MATLAB. The AeroSim simulation

environment features a complete nonlinear aircraft model with earth and atmospheric

models and models for propulsion, actuators, and sensors. Additionally, it features a von

Karman wind turbulence model already built into the aircraft model. Also, there are

model coefficients for the Aerosonde UAV already built for the user. The Aerosonde

aircraft is similar in size and shape to the UAVs that we have been using on our project

[14] (Figure 4.3). Due to the easy access to the Aerosonde model, the controllers in this

section will be developed and tested with respect to this model. Without a loss of

generality, the controllers would be able to be transferred over to our aircraft once we

have an aircraft model. A sample Simulink file of the simulator is shown in Figure 4.3.

Figure 4.2: Picture of the Aerosonde UAV [14]

Page 50: Path Planning UAV Sinus

41

Groundspeed X-axis

Groundspeed Y-axis

Groundspeed Z-axis

Roll rate p

Pitch rate q

Yaw rate r

Quaternion e0

Quaternion ex

Quaternion ey

Quaternion ez

Latitude

Longitude

Altitude

Fuel mass

Engine speed

[0 0 0]

Winds

0.5

Throttle

STOP

Stop Simulationwhen A/C on the ground

0

Sideslip

0

Rudder

0

Reset

R2D

R2D

R2D 0

Pitch angle

13

Mixture

1

Ignition

0

Flap0

Elevator

Demux

Demux

0

Bank angle

0

Airspeed

0

Aircraft states

0

Aileron

Controls

Winds

RST

States

Sensors

VelW

Mach

Ang Acc

Euler

AeroCoef f

PropCoef f

EngCoef f

Mass

ECEF

MSL

AGL

REarth

AConGnd

Aerosonde UAV

0

AOA

Figure 4.3: Simulink diagram of the aircraft simulation

The simulator also has the ability to be run in faster-than-realtime. The hardware-

in-the-loop (HIL) simulator discussed in the previous chapters had a limitation of having

to run in realtime. Now, with a rapid simulation environment, controllers can be

designed and evaluated at a much faster rate.

4.4 Current Autopilot

The current autopilot is built in Simulink and implemented on the MPC555 inside

of the Piccolo avionics using MATLAB Real-Time Workshop. The current autopilot was

then able to be put into a subsystem block and hooked up to the AeroSim aircraft model.

The actuator models were inserted on the outputs of the controller and the sensor outputs

were inserted into the inputs of the controller. Therefore, any changes made to the

existing autopilot can be uploaded into the Piccolo avionics with little or no changes in

their structure. The entire simulation setup is shown in Figure 4.4. Any commands that

the current autopilot is able to receive can be easily replicated in this Simulink

implementation.

Page 51: Path Planning UAV Sinus

42

Groundspeed X-axis

Groundspeed Y-axis

Groundspeed Z-axis

Roll rate p

Pitch rate q

Yaw rate r

Quaternion e0

Quaternion ex

Quaternion ey

Quaternion ez

Latitude

Longitude

Altitude

Fuel mass

Engine speed

Aerosonde UAV with piccolo controlSimulation sample time: 50 ms

Simulation time: 1.5 min.

Latitude

Longitude

Height

VNorth

VEast

WindSouth

WindWest

Pstat

Pdy n

OAT

P

Q

R

Ax

Ay

Az

Tracker Enable

Turn rate Enable

WP1 Latitude

WP1 Longitude

WP2 Latitude

WP2 Longitude

Alt Command

TAS Command

Turn Rate Command

Roll Angle

Pitch Angle

Yaw Angle

Altitude Estimate

TAS

Aileron out

Elevator out

Rudder out

Throttle out

Turn RateCommand

reduced piccolo autopilot

DEG RAD

DEG RAD

DEG RAD

DEG RAD

DEG RAD

Pitch rateYaw rateRollPitch

Turn Rate

Yaw to Turn

[0 0 0]

Winds

-122.35

WP2 Longitude

37.96

WP2 Latitude

-122.36

WP1 Longitude

37.98

WP1 Latitude

0

TurnRateComm

1

Turn rate Enable

0

Turn Rate Command

0

Tracker Enable

YawRate

time

BankAngle

Altitude

Throttle

Rudder

Elevator

Aileron

TurnRate

Va

alpha

beta

Longitude

Latitude

Throttle plot

30

TAS Command

0

TAS

STOP

Stop Simulationwhen A/C on the ground

0

Sideslip

Rudder plot

0

Reset

R2D

R2D

R2D

Pitch angle plot

0

Pitch angle

13

Mixture

1

Ignition

0

Flap

Elevator plot

Demux

Demux

Demux

Demux

Demux

Demux

Demux

Clock

Bank angle plot

0

Bank angle

Altitude plot

Altitude Est plot

500

Alt Command

Airspeed plot

0

Airspeed

0

Aircraft states

Aileron plot

Controls

Winds

RST

States

Sensors

VelW

Mach

Ang Acc

Euler

AeroCoef f

PropCoef f

EngCoef f

Mass

ECEF

MSL

AGL

REarth

AConGnd

Aerosonde UAV

Accelerometers

0

AOA

Vn

Ax

Ay

Az

Latitude

Longitude

Altitude

Ve

P

Q

R

Pstatic

Pdy n

OAT

Figure 4.4: Complete Simulink simulation setup with Piccolo autopilot

Page 52: Path Planning UAV Sinus

43

The current autopilot has control loops for both the longitudinal and lateral

dynamics of the aircraft. Longitudinal dynamics consist of the airspeed, pitch, and

altitude of the aircraft. Lateral dynamics consist of the roll, yaw, and turn rate of the

aircraft. Due to the goal of tracking a lateral path, the lateral control loops will be the

topic of discussion in this section.

The current lateral control is made of MIMO PID control on certain dynamics of

the aircraft. The main loops consist of the yaw rate fed to the ailerons and the yaw rate

fed to the rudder. The control law for the ailerons is given in Equation 4.9. It consists of

PID control on the yaw rate, PI control on the roll angle, and P control on the roll rate.

The pra term is to keep the derivative term, and in turn the controller, proper.

pKs

KKrr

ssp

KspK

Ksp

KK

pa

a

a

ra

ra

ra

ra

ra

PdesI

Pdesra

Ira

IP

ra

PD

a ⋅+−⋅

++−⋅

+

+

++

+

= )()()/1( 2

2

φφδ φ

φ

(4.9)

The control law for the rudder is given in Equation 4.10, and consists of PID

control on the yaw rate.

( )

)()1(

)1(

23

23

despa

IDrr

IPDPp

a

rr

P

r rasss

aKsaKp

aKaKsKKs

pK

rr

rrrr

rr

rrrrrrrr

rr

ψδ &−⋅+++

+

++++++⋅

=

(4.10)

The integral term of the controller has a washout filter attached to it (a terms), so low

frequency integral terms are attenuated and high frequency terms are allowed to pass.

The controller is built around the concept of a coordinated turn. A coordinated

turn is a turn in which there is no lateral specific force, ay [4]. The y-axis is the axis that

points out of the right wing on the aircraft. Therefore, the aircraft generally bank when

they turn, and the sideforce is maintained at a minimum. Sideforce is produced by the

sideslip velocity and rudder deflection. The condition for dynamic equilibrium of an

aircraft in a coordinated turn is shown in Figure 4.5.

Page 53: Path Planning UAV Sinus

44

Figure 4.5: Bank angle to turning radius in coordinated turn (constant altitude) flight

From Figure 4.5 it can be seen that there is a direct relationship between the

desired turn rate, ψ& , and the bank angle, φ . The rotational force, c, must have the

following relationship with the gravitational force.

g

VRgV

mgR

Vm

mgc ψ

φ&

====2

2

tan (4.11)

V

g φψ

tan=& (4.12)

Furthermore, one can find a relationship between the aircraft turn rate, ψ& , and the

angular velocities in the body fixed axes.

−−=

φθφθ

θψ

coscossincos

sin&

rqp

(4.13)

Therefore, given a desired turn rate desψ& , the desired roll angle can be found with

Equation 4.12. The desired roll rate is assumed to be zero because the aircraft should be

have a constant turn rate, although we can see some inconsistency with this assumption

and Equation 4.13 if there is a pitch angle on the aircraft.

The current turbulence rejection terms that are included in this controller are the

roll rate term in the aileron loop and the integral term on the yaw rate term in the rudder

loop. Basically, if there is a quick change in the roll or yaw, the controller should detect

it and adjust accordingly by giving a quick reaction with the ailerons or the rudder,

Lift

mg

φ

c

Page 54: Path Planning UAV Sinus

45

respectively. If turbulence is a problem, then the gains on these two control terms should

be increased therefore minimizing the effect of turbulence on the bank and yaw angle.

Simulations with the current autopilot were conducted in order to have a basis to

compare future results. Before running the simulations, the gains had to be adjusted for

controlling the Aerosonde UAV. The gains were kept at roughly the same ratios as that

of that the Rascal UAV run in the experiments in Chapter 3. The lateral autopilot gains

are set to: 2.0=raPK , 01.0=

raIK , 002.0=raDK , 1.0=

aPKφ

, 0=aIK

φ, 0=

paPK ,

15.0=rrPK , 02.0=

rrIK , and 002.0=rrDK .

In order to have consistent between the comparison of the different controllers,

tests will be run for two configurations. The first configuration will have no wind acting

on the aircraft. The second configuration will have the aircraft flying due north with an

average wind from the north of 5 m/s. The wind contains von Karman turbulence based

on altitude and mean wind speed. In all the simulations, the aircraft will try to maintain

zero turn rate. The initial conditions have the aircraft and its control surfaces flying

slightly off of trim values. The longitudinal controller will be kept the same throughout

the simulations; it will attempt to maintain a constant airspeed of 24 m/s and an altitude

of 490 m. The aircraft usually varies its airspeed from 20-30 m/s and the altitude from

450-500 m during this 15 second testing period, and may be worse if the lateral controller

is not performing well.

The figures that will be shown for the following simulations will all consist of the

same information. There will be five subplots shown: the top plot is the aileron control

effort, the second plot is the roll angle, the third plot is the yaw rate, r (darker line), and

the turn rate, ψ& (lighter line), the fourth plot is the rudder control effort, and the fifth plot

is the sideslip angle, β. One particular feature to look for will be that the yaw rate (or

turn rate) has good properties in terms of variance, steady state error, settling time, rise

time, etc. A couple of other important features to measure the controller performance

will be the control effort (aileron and rudder) expended, and that β should be zero for a

coordinated turn.

Page 55: Path Planning UAV Sinus

46

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-4

-2

0

φ (°)

0 5 10 15-1

0

1

r (°/s )

0 5 10 15-0.5

0

0.5

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.6: Simulation of current autopilot for desψ& = 0 and wind = 0

Figure 4.6 contains a simulation of the aircraft flying with no wind while trying to

maintain zero turn rate. The steady state error in yaw rate was approximately -0.76 rad/s

and the settling time was 1.95 seconds.

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-4

-2

0

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-1

0

1

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.7: Simulation of current autopilot for desψ& = 0 and wind = 5 m/s

Page 56: Path Planning UAV Sinus

47

Figure 4.7 contains a simulation of the aircraft flying with wind at 5 m/s. Here,

the steady state error was -1.15 rad/s and the average error after the initial transient period

was 0.03 rad/s. The two tests above can be used as a guideline as improvements are

attempted. The wind in the simulation is a slight head/cross wind aimed at the front right

corner of the aircraft.

4.5 Enhancement of Current Autopilot

The current autopilot has the capability of being enhanced using two relatively

straightforward methods. First, making use of different sensors than the ones that are

currently being used may enhance the autopilot. Second, filtering the current sensors and

adding additional loops may also improve the performance of the autopilot. This section

will first address the issue of using additional sensors.

4.5.1 Utilization of Additional Sensors

The avionics box has accelerometers in the x, y, and z directions that are currently

not being utilized. Turbulence effects the aircraft in the forces terms (X, Y, Z, L, M, N);

therefore if we could measure the deviation in these terms we could effectively cancel out

the turbulence with a reactive control surface deflection causing a force in the opposite

direction. Since lateral directional control is the primary concern, ay and az will be the

primary focus (ax will primarily effect the longitudinal dynamics). az will mainly be a

concern once the aircraft is turning, while ay is of concern all of the time.

Several controllers were attempted utilizing az connected to the ailerons. To name

a few, a filter was placed on az that filtered out the very high frequency noise above 15

Hz and filtered out the low frequency noise below 1 Hz. Then a P controller based on the

filtered az was added to the existing autopilot control loops and the gains were adjusted

accordingly. This controller did not help the performance of the autopilot, actually

increasing the turn rate deviation. The other controller for az added a derivative term in

order to negate fast changes in the z-acceleration. Again, this controller did not improve

performance by any means. Intuitively, the main benefit of this control would be in

Page 57: Path Planning UAV Sinus

48

heavy banked turns, and possible future implementations may try to feedback az to the

elevator or to the pair of ailerons acting in the same direction (flaperon control).

Acceleration in the y-direction has a much greater effect on lateral control;

therefore we expect a more fruitful attempt to improve performance by using ay. Recall

that during coordinated turns ay is zero; thus, we can always attempt to make ay zero. As

a result, coordinated turns will be enforced while still rejecting lateral disturbances.

The first attempt on improving performance using ay was using a washout filter

on the acceleration and then feeding it back to the rudder. The washout filter was set at

filtering out signals with a frequency smaller than 0.05 Hz. A bode magnitude plot of the

filter is shown in Figure 4.8. The goal was to filter out the low frequency terms and

reject high frequency turbulence. With this extra term, the performance was not

increased as far as achieving the yaw rate that we would desire, only in achieving

coordinated turns.

10-1

100

101

102

-25

-20

-15

-10

-5

0

Frequency (rad/s)

Ma gnitude (dB )

Figure 4.8: Washout filter placed on the accelerometer and roll angle

The second attempt using ay was using an integral term and feeding it back to the

rudder. The result for this controller based on no wind is shown in Figure 4.9 and with

the wind added in Figure 4.10.

Page 58: Path Planning UAV Sinus

49

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-4

-2

0

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-0.5

0

0.5

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.9: Simulation of current autopilot with enhancement of ay integral term

for desψ& = 0 and wind = 0

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-5

0

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-1

0

1

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.10: Simulation of current autopilot with enhancement of ay integral term

for desψ& = 0 and wind = 5 m/s

Page 59: Path Planning UAV Sinus

50

In comparing the controller with and without the ay integral term, little to no

improvement appears to be present. The turn coordination is more prevalent, and some

of the oscillations in r may be slightly more damped after the initial transient period.

4.5.2 Alternative Usage of Rate Gyros

As mentioned previously, in the current autopilot, the roll angle is calculated by

integrating the roll rate gyro in combination with GPS corrections. If there are sharp

changes in this estimated roll angle, there is a good chance that this would come from

turbulence acting on the wings of the aircraft. From experimental observation, this

turbulence appears to have a severe impact on how well the aircraft can hold a bank

angle, and thus a turn rate.

An additional loop was added to the autopilot that uses a washout filter (see

Figure 4.8) on the roll angle, φ . The gains were adjusted in order to get the best

performance and simulations were run as in the above experiments. Figure 4.11 contains

data from a simulation with no wind followed by Figure 4.12 with 5 m/s wind.

0 5 10 15-2

-1

0

δa (°

)

0 5 10 15-2

-1

0

φ (°)

0 5 10 15-1

0

1

r (°/s )

0 5 10 15-0.5

0

0.5

δr (°

)

0 5 10 15-0.2

0

0.2

β (°)

time (sec)

Figure 4.11: Simulation of current autopilot with filtered roll enhancement

for desψ& = 0 and wind = 0

Page 60: Path Planning UAV Sinus

51

0 5 10 15-2

-1

0

δa (°

)

0 5 10 15-4

-2

0

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-1

0

1

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.12: Simulation of current autopilot with filtered roll enhancement

for desψ& = 0 and wind = 5 m/s

4.5.3 Comparison of Enhancement Techniques

There are many measures to evaluate how well a controller performs. In

section 4.4, several measures of performance were listed. As all of the controllers in the

previous section used approximately the same control effort, this section will focus on the

performance of achieving the goal of tracking a desired yaw rate. The three best

performing controllers (current autopilot, additional ay integral term, additional filtered φ

term) will be compared using: steady-state error, maximum error, average error, settling

time, maximum error after settling, and average error after settling. Figure 4.13 depicts a

comparison of these three controllers in the no wind simulations. Figure 4.14 has a bar

graph comparison of the controllers with wind added to the simulation.

Page 61: Path Planning UAV Sinus

52

ss error max error avg error ts ts max error ts avg error0

0.5

1

1.5

2

2.5

3Current A/Pwith ay

term

with φ term

Figure 4.13: Comparison of the three controllers with no wind

ss error max error avg error ts max error ts avg error0

0.5

1

1.5

2

2.5

Current A/Pwith ay term

with φ term

Figure 4.14: Comparison of the three controllers with 5 m/s wind

Overall, the controllers with the “enhancements” did not perform exceptionally

better than the current autopilot. The ay controller (center bar) has noticeably worse

performance throughout the performance measures. The filtered φ controller appears be

Page 62: Path Planning UAV Sinus

53

slightly better at carrying out the control in the transient stages by having less maximum

and average error, but does not perform better after the controller has reached its settling

time.

Now that enhancements to the current autopilot have been evaluated, the next

approach will be a total redevelopment of the lateral autopilot. These controllers will not

use the existing autopilot; instead they will use a lateral model of the aircraft and models

of the entities that affect the lateral dynamics to come up with a new control law.

4.6 H2 Control Theory

The general control configuration that will be considered is the system shown in

Figure 4.15. This system contains the control variables, u, the measurements, v, the

exogenous signals, w, and the error signals, z. Exogenous signals are signals such as

disturbances and command inputs. The system can be defined in state-space form as

follows

uDwDxCy

uDwDxCzuBwBAxx

22212

12111

21

++=++=

++=&

, (4.14)

or can be decomposed as the following relationship with respect to the generalized plant,

P.

=

=

uw

sPsPsPsP

uw

sPvz

)()()()(

)(2221

1211 (4.15)

where the state-space realization of the P is given as

=

22212

12111

21

:)(DDCDDCBBA

sP (4.16)

The closed-loop transfer function from w to z is given by

wKPFz l ),(= (4.17)

Page 63: Path Planning UAV Sinus

54

where

211

221211 )(:),( PKPIKPPKPFl−−+= (4.18)

Figure 4.15: General control configuration with generalized plant, P, and controller, K

For H2 and H8 control some assumptions on the generalized plant must be true in

order for the algorithms to calculate the controllers. The assumptions are listed below:

(1) (A, B2, C2) are stabilizable and detectable

(2) D12 and D21 have full rank

(3) D11 = 0 and D22 = 0

(4)

121

2

DCBIjA ω

has full column rank for all ?

(5)

212

1

DCBIjA ω

has full row rank for all ?

H2 control involves the minimization of the H2 norm of the closed loop transfer

function, Fl(P,K) =: F. The 2-norm of closed loop transfer function, F, is found using

[11]

∫∞

∞−= ωωω

πdjFjFsF T )()(

21

)(2

. (4.19)

Alternatively, the H2 norm of a system can also be computed as

[ ] [ ] 2/12/1

2)()( BLBtrCCLtrG o

TTc == (4.20)

P

K

w z

u v

Page 64: Path Planning UAV Sinus

55

where C and B are the output/input matrices of the system’s state-space realization, Lc is

the solution to

0=++ TTcc BBALAL , (4.21)

Lo is the solution to

0=++ CCALLA Too

T , (4.22)

and A is the state matrix of the state-space realization [6].

The physical meaning of the H2 norm can have many interpretations. If the input

is a unit impulse, d, then the 2-norm of the output, z, equals the H2 norm. If the input, w,

is a signal with a 2-norm less than or equal to one, 12

≤w , then z will have a 2-norm

less than or equal to the H2 norm of the system [6]. In our particular application, since w

will have zero mean unit intensity white noise, the expected power of z can be given by

∫−∞→

T

T

T

Tdttztz

TE )()(

21

lim (4.23)

[ ]

Theorum) sParseval'(by

)()(21

)()(

2

2F

djFjF

tztztrE

T

T

=

=

=

∫∞

∞−ωωω

π (4.24)

Therefore, finding the H2 norm is equivalent to computing the variance of the output or

the power of the error signal. H2 control will minimize the output variance due to

exogenous inputs. In this application, this is a perfect match with the primary goals, as

we would like to minimize the effect of turbulence on the aircraft’s turn rate and, in turn,

its position.

H2 control is formulated as follows. This will be a brief overview; the reader is

directed to Doyle et al. [7] for complete derivation of this controller. Given the

Hamiltonian matrices, H2, and J2,

−−−

=TT

T

ACCBBA

H11

222 : (4.25)

Page 65: Path Planning UAV Sinus

56

−−−

=ABBCCA

J T

TT

11

222 : (4.26)

and their Riccati solutions, X2 := Ric(H2) and Y2 := Ric(J2). Define the following

matrices F2 := -B2TX2, L2 := -Y2C2

T, and A2 := A + B2F2 + L2C2. Then, the unique optimal

controller, Kopt is

−=

0:)(

2

22

FLA

sK opt (4.27)

4.7 H∞ Control Theory

Much like H2 control, H8 control finds a controller that minimizes its

accompanying norm. One of the major differences is that H8 control finds a suboptimal

control that establishes a controller that guarantees that the H8 norm is less than a certain

value. H2 control finds a unique optimal controller.

The H8 norm is the maximum singular value over all frequencies, ? . Therefore

for our closed loop system, Fl(P,K), the H8 norm is

( )))(,(max

),( ωσω

jKPFKPF ll =∞

(4.28)

The H8 norm can also be estimated using state-space methods with a search

procedure of finding the smallest ? > 0 such that H has no eigenvalues on the imaginary

axis [6], where H is defined as

−−=

TT

T

ACC

BBAH γ

1: (4.29)

There are several interpretations of the H8 norm. In the frequency domain, the

interpretation is that it is the maximum singular value of the closed loop transfer function.

In the time domain, if the input is a unit impulse, d, then the 8 -norm of the output, z, is

equal to the H8 norm of the plant. More importantly, for our case, the H8 norm is the

induced (worst case) 2-norm,

Page 66: Path Planning UAV Sinus

57

2

2

0)( )(

)(max),(

tw

tzKPF

twl ≠∞= (4.30)

where 2

⋅ is the 2-norm of the vector signal.

Finding a controller that minimizes the H8 norm is very similar to finding one to

minimize the H2 norm, in that they both can be compared in terms of how the variance of

the output signal will be shaped. For H2 control, we are finding the controller, K, such

that the expected value of 2

)(tz is a minimum,

{ }2

2)(min tzE

K (4.31)

For H8 control, we are finding the controller that minimizes the maximum of 2

)(tz over

all exogenous inputs w(t), or equivalently,

21

)(maxmin2

tzwK =

(4.32)

The solution to find the H8 controller is an iterative approach that finds all

stabilizing controllers, K, such that

γ≤∞

),( KPFl (4.33)

Here, the algorithm will be presented to calculate the H8 controller. Details are

left to the interested reader in Doyle et al. [7]. With the assumptions given in the

previous section, there exists a stabilizing controller, K, such that γ≤∞

),( KPFl if and

only if

(1) X8 = 0 is a solution to the algebraic Riccati equation

( ) 022112

11 =−+++ ∞−

∞∞∞ XBBBBXCCAXXA TTTT γ (4.34)

(2) Y8 = 0 is a solution to the algebraic Riccati equation

( ) 022112

11 =−+++ ∞−

∞∞∞ YCCCCYBBAYAY TTTT γ (4.35)

such that ( )[ ] iCCCCYA TTi ∀<−+ −

∞ 0Re 22112γλ

Page 67: Path Planning UAV Sinus

58

(3) 2)( γρ <∞∞YX (4.36)

where )(max:)(1

MM iniλρ

≤≤= is the spectral radius of M.

All the controllers are given by K = Fl(Kc,Q), where

−= ∞

∞∞∞∞

00

2

2

ICIFBZLZA

K c (4.37)

∞∞ −= XBF T2 , TCYL 2∞∞ −= , 12 )( −

∞∞−

∞ −= XYIZ γ , (4.38)

22112 CLZFBXBBAA T

∞∞∞∞−

∞ +++= γ , (4.39)

and Q(s) is any stable proper transfer function such that γ<∞

Q .

Luckily, MATLAB has both the H2 and H8 control algorithm implemented such

that they are easy to use. For the H2 control, MATLAB solves the two algebraic Riccati

equations, and returns the optimal controller. For the H8 control, the user can specify a ?

that they would like to achieve and then MATLAB performs the iterations and returns a

controller that achieves the smallest ? possible. In order to use this theory, the user must

specify weights on the inputs and outputs of the generalized system, (4.15). This is

usually where the difficulty arises, and is often why many people shy away from using H2

and H8 control. In this framework, the exogenous signals and the errors are modeled as

the unit ball in L2, filtered by these weighting functions to represent the actual signals in

the system.

4.8 Weighting Functions

In order to use H2 and H8 control effectively, weighting functions must be

integrated into the interconnected system to ensure that the controller is designed

correctly. This section will go through the weighting functions for each part of lateral

control design. Suggested references for creating weighting functions are papers by

Doyle and others, such as [2, 8].

Page 68: Path Planning UAV Sinus

59

4.8.1 Actuator Models and Weights

The first limitation on our system that is addressed is the bandwidth of the

actuators. The ailerons and rudders both have servos that move the control surface. Due

to the likelihood that the ailerons will need a higher bandwidth servo, the ailerons are

provided with servos that have a bandwidth of approximately 10.47 rad/s. The rudder’s

servo has a bandwidth of 6.16 rad/s. Each actuator is then modeled with a second order

transfer function featuring the natural frequency of the actuator at the bandwidth value

with a damping ratio of 0.707. The mechanical model for the aileron is given by

2aaa

2

2a

a 2 ωωξω

++=

ssW (4.40)

where ? a = 10.47 rad/s and ?a = 0.707. The model for the rudder is

2rrr

2

2r

r 2 ωωξω

++=

ssW (4.41)

where ? r = 6.16 rad/s and ?r = 0.707.

The actuator models also have a delay model attached to the mechanical model.

The delay model represents the delay from the digital implementation of the controller.

The control has a sample time of 0.05 sec; therefore the model is given a natural

frequency of ? del = 125.7 rad/s and a damping coefficient of ?del = 0.866. The transfer

function for the delay weighting function is given as

2deldeldel

2

2deldeldel

2

delay 22

ωωξωωξ

+++−

=ssss

W . (4.42)

The complete model for an actuator is shown in Figure 4.16.

Figure 4.16: Model of actuator with delay and mechanical model

Wdelay Wa or Wr aδ rδ

aδ&

aδ&&rδ&

rδ&&

or comaδ comrδor

Page 69: Path Planning UAV Sinus

60

The models of the actuators are converted into their state-space representations in

order to extract the position, velocity, and acceleration of the actuators. These state-space

representations are stored in blocks called Wactail and Wactrud, for the aileron and rudder,

respectively, for interconnection with other blocks in the system.

In order to limit the control effort, the position, velocity, and acceleration of the

actuators will be penalized in a weighting function, Wact. Wact is based on some hard

constraints of the actuators. The position of the aileron is limited to ±15º and the rudder

is limited to ±15º. The velocity of the aileron is limited to 10 rad/s and for the rudder 7

rad/s. The acceleration of the aileron is limited to 200 rad/s2 and rudder is limited to 140

rad/s2. In context of the H2 and H8 control context, the actuator signal levels will be

treated as errors, and should remain small when there is disturbances and sensor noise.

The inverse of the limits in actuator states will be multiplied with the actual actuator

states to give a normalized error signal that will be desired to have a 2-norm less than 1.

Wact is then given as follows, which is multiplied by the actuator states as in Equation

4.44 to give the actuator error, eact.

)007.0 ,15.0 ,82.3 ,005.0 ,1.0 ,82.3(act diagW = (4.43)

=

r

r

r

a

a

a

We

δδδδδδ

&&&

&&&

actact (4.44)

4.8.2 Sensor Models and Weights

The sensors available for measuring lateral states are the accelerometer in the y-

direction, outya , the roll rate gyro, pout, and the yaw rate gyro, rout. Additionally, the roll

angle, outφ , is calculated by integrating rout and performing some other schemes to

eliminate the bias and error from the integration [5]. Thus, the roll angle calculations

have more error than the rate gyro has itself.

Page 70: Path Planning UAV Sinus

61

The sensors are modeled such that the noise level increases with frequency. The

measurements from the sensors are assumed to be the nominal state, plus additive colored

noise that goes through a weighting function. Therefore, the sensor measurements are

modeled as

yayayy wWaa +=out

(4.45)

pp wWpp +=out (4.46)

rr wWrr +=out (4.47)

φφφφ wW+=out (4.48)

where w(.) are exogenous signals of zero mean, unit intensity white noise.

The weighting function for the accelerometer is modeled with lower noise at

lower frequencies. The model for the accelerometer is

11.0120

072.0++

=ss

W ya , (4.49)

which implies that at frequencies less than 0.006 Hz there is 0.072 m/s2 inaccuracy

leading up to frequencies higher than 5 Hz with 2.9 m/s2 inaccuracy. Realistically, the

error approaches infinity as the frequency does likewise, but the weighting function

levels off in order to prevent undesirable error amplification at high frequencies that

would not allow us to achieve ?.

The weighting function for the rate gyros will be the same for both the roll and

yaw rate gyros, as the same sensor is used for both axes in the aircraft.

121100

0003.0++

==ss

WW rp , (4.50)

which implies that at frequencies less than 0.015 Hz there is 0.0003 rad/s inaccuracy

leading up to frequencies higher than 0.1 Hz with 0.015 rad/s inaccuracy.

The weighting function for the roll angle is similar to the rate gyro due to the

direct relationship that they have. The error in the roll angle is higher due to the

Page 71: Path Planning UAV Sinus

62

integration scheme, especially at high frequencies; therefore the weighting function

reflects this result.

15.01100

0007.0++

=ss

Wφ (4.51)

which implies that at frequencies less than 0.015 Hz there is 0.0007 rad inaccuracy

leading up to frequencies higher than 5 Hz with 0.14 rad inaccuracy. The frequency

response plot for the Euler angles are shown in Figure 4.17 along with the rate gyros and

the accelerometers. The sensor noise weighting functions are combined into a block

diagonal matrix to be used as the weighting function, Wnoise.

10-4

10-3

10-2

10-1

100

101

102

-80

-70

-60

-50

-40

-30

-20

-10

0

10

Ma gnitude (dB )

Bode Diagram

Frequency (rad/sec)

a

φ, θ, ψ

p, q, r

Figure 4.17: Frequency response of sensor models

4.8.3 Wind Model and Weights

As rejection of wind disturbances are the main focus of this chapter, we must

come up with a model for how wind effects the aircraft. Fortunately, there are many

sources for wind models based upon empirical data that consist of passing band-limited

white noise through appropriate forming filters. The turbulence models are scaled with

respect to altitude, aircraft velocity, wing span, and severity of disturbances. Three of the

Page 72: Path Planning UAV Sinus

63

major models that are used today for turbulence models for aircraft are the von Karman

turbulence model [17], the Dryden turbulence model, and the turbulence model found in

Holley [4]. As previously mentioned, the von Karman turbulence model is used in the

simulator. Here, latter of the three models will be developed to model the wind as a

weighting function.

The wind models are decomposed into the body axes; therefore, for lateral control

we can focus on the model for the side gust velocity, vw, and roll gust velocity, pw.

Although the yaw gust velocity is usually assumed small enough to neglect, a rough

model will be included in order to make sure that the controller does not excite any

angular velocity disturbances.

The side gust velocity can be modeled by

32

23

)/()/()()(

cVsLcVsLc

Qswsv

W vv

wv

w

w ++== (4.52)

where 3/4

3/2

3)1(

ββ+

=c , 3/42 231

ββ+

=c , Lb 2/:=β , ft2500

)ft2000(+

≅h

hL , altitude=h ,

span wing=b , elocityaircraft v=V , V

Lcc

Q vv

2

3

22σ

= , and =vσ RMS gust velocity. The

RMS gust velocity is based upon the conditions in the atmosphere and the velocity of the

wind. Using the von Karman model [17], the RMS gust velocity given a certain mean

wind velocity, VW, becomes

( ) 4.0000823.0177.0

1.0

h

VWv

+=σ (4.53)

where h and VW are in ft and ft/s, respectively. Also, h is the altitude above the ground

level, which in the following derivation is assumed to be sea level. The following are the

values for our aircraft and test flight condition: b = 2.8956 m, h = 490 m, L = 239 m, V =

24 m/s, 006.0=β , VW = 10 m/s, 69.6=vσ ft/s, ft/s 2.51=vQ . The frequency response

of this coloring filter (weighting function) for the side gust velocity is shown in Figure

4.18.

Page 73: Path Planning UAV Sinus

64

10-2

10-1

100

101

102

103

-100

-80

-60

-40

-20

0

20

Frequency (rad/s)

Ma gnitude (dB )

Figure 4.18: Frequency response of the side gust velocity weighting function, wvW

The roll gust velocity, pw, is modeled in a very similar fashion as the side gust

velocity. The dynamic model is given by

1)2.1/(

1)()(

+==

VsbQ

swsp

W pp

wp

w

w (4.54)

where rad/s 002.035 24

=

=

LVQp

σusing the flight condition listed above, using the same

s as for the side gust velocity. The yaw gust velocity, rw, will use the same model as the

roll gust velocity for simplicity. The bode magnitude plot of the roll gust velocity model

is shown in Figure 4.19. The wind models are combined to output the wind states for the

aircraft model as

windwind

r

p

v

r

p

v

w

w

w

wWwww

WW

W

rpv

w

w

w

w

w

w

:00

0000

=

=

(4.55)

Page 74: Path Planning UAV Sinus

65

10-1

100

101

102

103

-65

-60

-55

-50

-45

-40

-35

-30

-25

Frequency (rad/s)

Ma gnitude (dB )

Figure 4.19: Frequency response of the roll gust velocity weighting function, wpW

(equivalently, the weighting function for yaw gust velocity, wrW )

4.8.4 Autopilot Command Weight

The goal of the controller will be to follow a desired yaw rate, rcmd, which is

similar to following the desired turn rate, desψ& , discussed in section 4.4. The yaw rate

and turn rate have a relationship that was shown in Equation 4.13, which are almost the

same as long as the pitch angle and the roll angle are small. The autopilot will command

rcmd, varying from -10 to 10 °/sec. The autopilot will only command these signals at a

rate of 0.05 sec or slower. The largest command that should be followed is a difference

of 18.25 °/sec or 0.319 rad/s. Furthermore, these commands will be mainly at low

frequencies and will be assumed to given only up to about every 250 ms. This will give

us the cutoff frequency and a model,

1

101.0319.0

++

=s

sW

cmdr (4.56)

Page 75: Path Planning UAV Sinus

66

In other words, the model has a magnitude of 0.319 rad/s at frequencies up to the cutoff

frequency, and then decay to negligible values.

The autopilot commands are then represented by

cmdcmd rrcmd wWr = (4.57)

The frequency plot shown in Figure 4.20 gives a pictorial representation of the model.

10-2

10-1

100

101

102

103

104

-50

-45

-40

-35

-30

-25

-20

-15

-10

-5

Ma gnitude (dB )

Bode Diagram

Frequency (rad/sec)

Figure 4.20: Frequency response of the autopilot command weighting function, cmdrW

4.8.5 Ideal Command Response

Ideally, the controlled lateral model would have an instantaneous response. As

that is completely impractical, we must settle for a response much like a second-order

system. In order to get a ballpark estimate of how we would like the controlled system to

behave, we can look at how the aircraft responds to current autopilot control in Figure

4.6. From looking at the response, a rough estimate for the response is a settling time of

2 seconds with little to no overshoot. One possible set of parameters for the second-order

system of the form

Page 76: Path Planning UAV Sinus

67

2idealidealideal

2ideal

ideal 21 ωωζω

++=

sr (4.58)

would be to have 3cmd =? rad/s and 8.0cmd =? . The step response of this second-order

system is illustrated in Figure 4.21 and is slightly better than that of the current autopilot.

0 0.5 1 1.5 2 2.50

0.2

0.4

0.6

0.8

1

1.2

1.4Step Response

Time (sec)

Am plitude

Figure 4.21: Step response of the ideal second-order system that the yaw rate of the

aircraft should imitate

4.8.6 Performance Weights

With a desired response in hand, it is now necessary to specify how well the

system should follow that response. Basically, it is possible to define a yaw rate error

signal, r – rideal that should be kept “small”. Again, we will need to scale what is meant

by “small” into that which can be used by H8 control methodology. The yaw rate error

will be weighted by a frequency dependent weight of

1100

1500

++

=s

sW

errorr (4.59)

Page 77: Path Planning UAV Sinus

68

The weighting corresponds to allowing approximately 0.002 rad/s inaccuracy at low

frequencies, and allowing 0.2 rad/s inaccuracy at higher frequencies. The bode

magnitude plot for the yaw rate error weighting is shown in Figure 4.22.

10-4

10-3

10-2

10-1

100

101

102

10

15

20

25

30

35

40

45

50

55

Ma gnitude (dB )

Bode Diagram

Frequency (rad/sec)

Figure 4.22: Frequency response of the yaw rate error weighting function, errorrW

The bank angle error can be defined in terms of the yaw rate because we would

like the aircraft to be in a coordinated turn. The relationship between r and φ can be

computed from Equations 4.12 and 4.13 as

=⇒== −

gVr

gVr 1sincoscos

sintan φ

φφφ

φ (4.60)

With the aircraft flying at V = 24 m/s,

(rad) 5.2 r≅φ (4.61)

Thus, the bank angle error can be defined as r5.2−φ . The weighting function for that

error will use the same frequencies, but with less need for accuracy

1100

180

++

=s

sW

errorφ (4.62)

Page 78: Path Planning UAV Sinus

69

During a coordinated turn and in order to assist in reject disturbances, the lateral

acceleration, ay, should be zero. Therefore, ay will define an error within itself. The

weighting function for the lateral acceleration error is

1100

18

++

=s

sW

errorya (4.63)

This weighting on the error permits accelerations up to 0.125 m/s2 for low frequencies

and 12.5 m/s2 for high frequencies. The shape of the weighting for both the bank angle

error and acceleration error are the same as the yaw rate error weight in Figure 4.22, the

magnitudes are the only difference. The entire performance error becomes

=

−−

=

ideal

y

perf

y

ideal

a

r

perf

r

ra

Wa

rrr

WW

We

errory

error

error

φφφ 5.2

000000

(4.64)

4.9 Interconnected System

The next step in the H2 and H8 control process is to connect the weighting

functions and models together in order to get a system in the form of general control

configuration shown in Figure 4.15, and repeated here for convenience.

Figure 4.23: General control configuration

The complete interconnected system, which becomes the generalized plant, P, is

shown in Figure 4.24.

P

K

w z

u v

Page 79: Path Planning UAV Sinus

70

Figure 4.24: The interconnected system comprised of all of the weights and models that

make up the generalized plant, P

The output labeled with an e are the error signals and corresponds to z in Figure 4.23.

The inputs labeled with w are the exogenous signals from the disturbances and noise.

The signals that go into and come out of the controller are shown in Figure 4.25 for

clarity.

Figure 4.25: Representation of the controller, K, with input and output signals

eperf

cmdr

Linearized Aircraft Model

eact

Wwind

Aileron model

Rudder model

Wnoise

Ideal 2nd order

system

Wrcmd

Wact

comaδ

comrδ

+

Wperf

sensorsout

windw

wnoise

cmdrwidealr

rqpay ,,,

K

rcmd

ayout pout rout outφ

comaδ

comrδ

Page 80: Path Planning UAV Sinus

71

4.10 Simulation Results and Discussion

4.10.1 H2 Control Simulation and Results

The H2 controller, K2, was developed using the interconnected system and the

algorithm presented in section 4.6. The resulting controller is 26 states, the same number

of states as the interconnected system. Recall, that this controller is optimal with respect

to a minimum variance response in terms of turbulence, sensor noise, actuator bandwidth

constraints, and commands from the autopilot. Due to its complexity, the controller will

not be displayed.

An equally suitable controller can be created by performing a balanced realization

on the controller and eliminating the states with small Hankel singular values. The

Hankel singular values of the controller are shown in Figure 4.26.

0 5 10 15 20 2510

-6

10-5

10-4

10-3

10-2

10-1

100

101

102

103

"Balanced" State

Hankel Sin gular Value

Figure 4.26: Hankel singular values of the H2 controller, K2, with the balanced states

Looking at the Hankel singular values, one can see that there is a big drop after

the first state, but that is most likely not adequate for truncation. There appears to be a

Page 81: Path Planning UAV Sinus

72

fairly constant slope up until the 16th state. First, it was attempted to truncate the

controller after the 16th state, but that yielded a controller that, when combined with the

entire system in closed loop form, had an undesirable frequency response. The controller

was ultimately truncated after the 20th state. The controller was then put into closed loop

form with the entire system and the frequency response was computed. The norm of the

closed loop transfer function frequency response versus frequency is shown in Figure

4.27.

10-4

10-3

10-2

10-1

100

101

102

103

0

0.2

0.4

0.6

0.8

1

1.2

1.4

Frequency (rad/s)

H-inf Norm

Figure 4.27: H∞ norm of the closed loop system with the reduced controller, K2red

The H∞ norm of the reduced system is not visibly different from that with the non-

reduced controller. Here, the H∞ norm is used as an easy measure of looking at how the

closed loop system will behave and is used to evaluate the H2 controller even though it

was not developed using H∞ techniques. From the above plot, it is apparent that the

maximum singular value is γ = 1.28 > 1. This would imply that there exists a controller

that would have a larger variance than desired at a given frequency; nevertheless the

controller is still optimal in the sense of the H2 norm.

Page 82: Path Planning UAV Sinus

73

The controller was first tested with the linear model of the aircraft at the trimmed

flight condition. The yaw rate response is shown in Figure 4.28 for a command of 5°/sec

yaw rate. After a large spike in the transient, the system behaved much like the ideal

second order model. Therefore, the response appears to be good, and we can then try the

controller on the nonlinear plant

0 1 2 3 4 5 6 7 8 9 100

1

2

3

4

5

6

7

8

9

10

r (°/s )

time

Figure 4.28: Yaw rate response for the linear aircraft model with the controller K2red

0 5 10 15-20

0

20

δa (°

)

0 5 10 15-200

-100

0

φ (°)

0 5 10 15-50

0

50

r (°/s )

0 5 10 15-20

0

20

δr (°

)

0 5 10 15-50

0

50

β (°)

time (sec)

Page 83: Path Planning UAV Sinus

74

Figure 4.29: Response of the nonlinear system with the discrete controller

implementation of K2red

The control K2red was then inserted into the autopilot and simulations with the

nonlinear aircraft model were performed. The command for the autopilot was to

maintain steady flight with no turn rate. The longitudinal control is that same as what is

in the current autopilot system, and the only initial disturbance is that the aircraft is not

flying at trim. There is no wind in this simulation, and the controller is implemented in

discrete time. The result of the simulation is shown in Figure 4.29.

The controller did not behave very well, as the reaction from the controls appears

to be too severe. Eventually, the control surfaces saturate to their maximum value and

the system returns to stable flight. Overall, this controller performed very poorly. Part of

the poor performance could be due to the discrete-time implementation of the controller,

and due to the fact that the longitudinal controller cannot hold a steady 24 m/s at 490

meters altitude. The H∞ control will now be evaluated to see if we get better

performance.

4.10.2 H∞ Control Simulation and Results

Using the interconnected system developed above, the state-space iteration was

run in MATLAB to achieve a suboptimal H∞ controller. The controller that was found

had 26 states, same as the H2 controller. The maximum singular value of the closed loop

system over all frequencies was found to be γ = 0.625 < 1. A balanced realization of the

controller, K∞, was performed in order to truncate the number of states. The Hankel

singular values are shown in Figure 4.30. The proper truncation spot that still maintained

a controller with γ < 1 was after the 18th state. All prior truncations yielded a closed loop

system with a maximum singular value greater than one. The norm of the closed loop

transfer function frequency response versus frequency is shown in Figure 4.31. The H∞

norm is slightly higher with the reduced order system at 0.71.

Page 84: Path Planning UAV Sinus

75

0 5 10 15 20 2510

-6

10-5

10-4

10-3

10-2

10-1

100

101

102

103

"Balanced" State

Hankel Sin gular Value

Figure 4.30: Hankel singular values of the H∞ controller, K∞, with the balanced states

10-2

10-1

100

101

102

103

0

0.1

0.2

0.3

0.4

0.5

0.6

0.7

0.8

Frequency (rad/s)

H-inf Norm

Figure 4.31: H∞ norm of the closed loop system with the reduced controller, K∞red

The controller, K∞red, was linked with the linear aircraft model and a simulation

was performed with a commanded yaw rate of 5°/sec. The response was very similar to

Page 85: Path Planning UAV Sinus

76

that of the H2 controller. There was a larger spike in the transient with a slight more

oscillation about the steady state value.

0 1 2 3 4 5 6 7 8 9 10-2

0

2

4

6

8

10

12

14

16

r (°/s )

time

Figure 4.32: Yaw rate response for the linear aircraft model with the controller K∞red

K∞red was connected in the autopilot and simulations were performed with the

nonlinear plant. The initial conditions were the same as in the previous runs, and the

controller was put into discrete form. The response is shown in Figure 4.33.

0 5 10 15-20

0

20

δa (°

)

0 5 10 15-200

-100

0

φ (°)

0 5 10 15-200

0

200

r (°/s )

0 5 10 15-20

0

20

δr (°

)

0 5 10 15-20

0

20

β (°)

time (sec)

Figure 4.33: Response of the nonlinear system with the discrete controller

implementation of K∞red

Page 86: Path Planning UAV Sinus

77

K∞red had difficulty maintaining the yaw rate at zero. Again, it appears as though

the gains are too large. The oscillations of the control surfaces indicate that the system is

probably reacting too much at a time. To see if the nonlinearities or the discrete time

implementation is the main problem, the controller was implemented in its continuous

form and the response is shown in Figure 4.34.

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-5

0

5

φ (°)

0 5 10 15-5

0

5

r (°/s )

0 5 10 15-5

0

5

δr (°

)

0 5 10 15-1

0

1

β (°)

time (sec)

Figure 4.34: Response of the nonlinear system with the continuous controller

implementation of K∞red

As suspected, the performance is improved by implementing a continuous time

controller. The oscillations are still very rapid, but due to the elimination of the

restriction on sampling time, the system does not get as far away from zero yaw rate.

Also, the control surfaces have much less deflection. Still, the system does not behave in

a satisfactory manner.

The next approach is to try changing some of the weighting functions in order to

get better reaction from the controller. Often, people associate the weighting functions of

H∞ control to the tuning knobs of the gains on a PID controller. To get less of a control

response, the weightings on the actuators will be increased to

Page 87: Path Planning UAV Sinus

78

)025.0 ,4.0 ,73.5 ,02.0 ,36.0 ,73.5(act diagW = (4.65)

Also, to try and eliminate the spike in response at the beginning of a commanded turn

rate (see Figure 4.32), the acceleration will be penalized more and the bank angle error

will be penalized less. (Replace 8 in Equation 4.63 with 12, and replace 80 in Equation

4.62 with 20). Increasing the weighting on the acceleration any higher yields an

undesirable controller in terms of the H∞ norm. The new controller, K∞new, was

developed using the same scheme and the resulting response is shown in Figure 4.35.

0 5 10 15-2

0

2

δa (°

)

0 5 10 15-10

-5

0

φ (°)

0 5 10 15-1

-0.5

0

r (°/s )

0 5 10 15-5

0

5

δr (°

)

0 5 10 15-5

0

5

β (°)

time (sec)

Figure 4.35: Response of the nonlinear system with continuous controller implementation

of K∞new

It is readily apparent that the performance of the system has better characteristics

in terms of its oscillations and control efforts. The problem that arises with this new

control is the increasing steady state error, which could lead to instability of the nonlinear

system. A possible application of this new controller would be to use it for the transient

stages, and switch over to the current autopilot for longer periods of time. In other

words, filter out the high frequency signals and give them to the H∞ controller, and filter

out the low frequency signals and give them to the PID controller.

Page 88: Path Planning UAV Sinus

79

4.11 Gain-scheduling H∞ Control

This section attempts to improve the performance of the H∞ controller using a

gain scheduling approach where the autopilot switches between different H∞ controllers

based on the state of the aircraft. One of the problems with the above simulations could

be due to the longitudinal autopilot not keeping the aircraft close enough the linearization

point and therefore a different control law should be used at these other states.

In order to build a gain scheduling H∞ controller, the model is linearized at h =

490 m, V = 20-30 m/s, φ = 0° at intervals of 2 m/s. The H∞ controllers at each of these

states are developed in the same method as section 4.10. Therefore there are 10 different

controllers and they are scheduled with the change in airspeed. Figure 4.36 shows a

diagram of how the controllers are implemented based on airspeed. The scheduling is

similar to fuzzy control, in which a percentage of control is used based on the distance

from the nominal state of the system. The sum of the controls then equals 100% control,

with part of the control possibly coming from two different controllers (i.e. 25%/75% or

90%/10%).

Figure 4.36: H∞ gain scheduler

100%

0%

Percentage of control

Airspeed (m/s)

20 30 24 28

Page 89: Path Planning UAV Sinus

80

Simulations were performed using the gain scheduling H∞ controller for scenarios

similar to the above sections. The response of the aircraft in no wind is shown in Figure

4.37. It is apparent that, the aircraft was able to maintain zero turn rate with little control

effort.

0 5 10 15-1

-0.5

0

δa (°

)

0 5 10 15-2

0

2

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-1

0

1

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.37: Simulation of gain scheduling discrete H∞ controller for desψ& = 0 and

wind = 0 m/s

Due to the success of the controller with no wind present, wind was added to the

simulation to observe whether the controller is able to reject turbulence. The simulation

with the nonlinear aircraft model subjected to a 5 m/s head/cross wind is shown in Figure

4.38. Again, the controller is able to stabilize the aircraft with minimal control effort.

Page 90: Path Planning UAV Sinus

81

0 5 10 15-1

-0.5

0

δa (°

)

0 5 10 15-2

0

2

φ (°)

0 5 10 15-2

0

2

r (°/s )

0 5 10 15-1

0

1

δr (°

)

0 5 10 15-0.5

0

0.5

β (°)

time (sec)

Figure 4.38: Simulation of gain scheduling discrete H∞ controller for desψ& = 0 and

wind = 5 m/s

A comparison of the gain scheduling H∞ controller with the current autopilot

(simulations shown in section 4.4) is illustrated in Figures 4.39 and 4.40. The first chart

is a no wind comparison of the steady-state error, maximum error, average error, settling

time, maximum error after settling, and average error after settling as in section 4.5. The

second chart compares the two controllers with wind present. Overall, the gain

scheduling controller improves the performance in terms of steady-state error and

maximum error in the presence of wind. This indicates that there would be better overall

tracking of a desired turn rate. The gain scheduling H∞ controller does have a slightly

longer settling time in the disturbance-free case. The difference is negligible compared to

the benefits that the controller gives in the presence of wind. Additionally, compared to

the other H∞ controllers developed above, this controller is discrete; therefore, it will be

easy to implement with the autopilot for the actual aircraft. By and large, the gain

scheduling H∞ controller is a great improvement for controlling the aircraft in turbulence.

Page 91: Path Planning UAV Sinus

82

ss error max error avg error ts ts max error ts avg error0

0.2

0.4

0.6

0.8

1

1.2

1.4

1.6

1.8

2

Current AutopilotGain Scheduling Control

Figure 4.39: Comparison of current autopilot and gain scheduling H∞ controller

with no wind

ss error max error avg error ts max error ts avg error0

0.2

0.4

0.6

0.8

1

1.2

1.4

1.6Current AutopilotGain Scheduling Control

Figure 4.40: Comparison of current autopilot and gain scheduling H∞ controller

with 5 m/s wind

Page 92: Path Planning UAV Sinus

83

4.12 Future Work

There is still area for future work in disturbance rejection control of aircraft. This

chapter outlined the basic approaches for improving the performance of the autopilot in

the presence of turbulence.

The results in the last section still need to be implemented on an actual aircraft

and tested experimentally. Furthermore, additional tests of different wind scenarios,

initial states of the aircraft, and desired states of the aircraft would be beneficial to

confirm that the controller improves the performance in all cases.

Another controller that could be used for disturbance rejection would be a

reflexive controller that uses accelerometers placed in the wings of the aircraft. When a

gust comes along, the accelerometers would report a force to the autopilot and the

ailerons could be moved accordingly. It would be reflexive in the sense that when the

wings are hit with a force, the ailerons are moved as a reflex to cancel out the force.

Work improving the constant wind estimation would also improve the ability for

the UAVs to follow the desired paths. Often it is the constant wind estimation algorithm

that is the cause of the deviation. Although this thesis did not cover the issues of constant

wind estimation and only briefly dealt with wind compensation issues, these are

important areas for future research.

One important test that still needs to be conducted is testing the actual UAVs with

the current autopilot’s turbulence loops increased. Better performance may be able to be

achieved if the gains of these control loops are increased.

Page 93: Path Planning UAV Sinus

84

Chapter 5

Conclusions

A strategy has been presented for path planning for single and multiple UAV

groups. The strategies developed assured that the UAVs would pass over a point of

interest with a specified frequency. The point of interest was allowed to move in any

direction and at any speed up to the speed of the UAVs; furthermore, its movement was

not predefined. Constant wind compensation was addressed for a single UAV. The path

planning algorithms have been confirmed using simulations and experiments.

With the path planning algorithms at hand, the main problem in controlling the

UAVs to follow the path came in the presence of turbulence and wind. The turbulence

problem was addressed by utilization of the sensor platform on the UAV in order to get

better rejection of the turbulence. The current autopilot was examined, and

enhancements to the autopilot were considered and simulated. The enhancements

outlined several approaches in attempting to deal with disturbances in the presence of

sensor noise.

H2 and H∞ control theory was presented and applied to the turbulence problem.

Weighting functions were developed in order to put together a generalized control

configuration. Minimum variance controllers were developed in the presence of actuator

limitations, wind disturbances, sensor noise, and autopilot commands. The controllers

were simulated and compared with the current autopilot. The H2 controller did not yield

better results. The standard continuous H∞ controller yielded better results in the

Page 94: Path Planning UAV Sinus

85

transitory period, but had increasing steady state error. The gain scheduling discrete H∞

controller greatly improved the aircraft’s performance over the current autopilot.

Page 95: Path Planning UAV Sinus

86

Bibliography

[1] M. Abramowitz and I.A. Stegun, Handbook of Mathematical Functions, Dover

Publications, 1965, 17.6.

[2] G. J. Balas, J. C. Doyle, K. Glover, A. Packard, and R. Smith, “µ-analysis and

synthesis toolbox user’s guide”, version 3, The MathWorks, Inc., 2001.

[3] H. W. Bode, Network Analysis and Feedback Amplifier Design, D. Van Nostrand

Co., 1945.

[4] A. E. Bryson, Control of Spacecraft and Aircraft, Princeton University Press,

1994.

[5] CloudCap Technology – Piccolo avionics system for small Unmanned Aerial

Vehicles. http://www.cloudcaptech.com/piccolo.htm, 2001-2003.

[6] J. C. Doyle, B. Francis, and A. Tannenbaum, Feedback Control Theory,

Macmillan Publishing Company, 1992.

[7] J. C. Doyle, K. Glover, P. P. Khargonekar, and B. A. Francis, “State-space

solutions to standard H2 and H∞ control problems”, IEEE Transactions on

Automatic Control, 34(8): 831-847, August 1989.

[8] J. Doyle, K. Lenz, and A. Packard, “Design examples using µ-synthesis: Space

shuttle lateral axis FCS during re-entry”, NATO ASI Series, Modelling,

Robustness, and Sensitivity Reduction in Control Systems, vol. 34, Springer-

Verlag, 1987.

[9] B. Etkin, Dynamics of Flight – Stability and Control, John Wiley & Sons, Second

Ed., 1982.

Page 96: Path Planning UAV Sinus

87

[10] D.A. Schoenwald, “AUVs: In space, air, water, and on the ground”, IEEE

Control Systems Magazine, 20(6):15-18, December 2000.

[11] S. Skogestad and I. Postlethwaite, Multivariable Feedback Control, John Wiley

& Sons, 1996.

[12] S. C. Spry, “Modeling and control of vehicle formations”, Ph.D. Thesis,

University of California, Berkeley, 2002.

[13] Unmanned Aerial Vehicles Roadmap: 2002-2027, Office of the Secretary of

Defense, December 2002.

[14] Unmanned Dynamics, LLC, AeroSim Blockset User’s Guide, version 1.1.

http://www.u-dynamics.com, 2002-2003.

[15] U.S. Army, “America’s War on Terror: Special Issue”, Soldiers: U.S. Army

Magazine, http://www.army.mil/soldiers/sep2003/Sept03.pdf, September 2003

[16] U.S. Coast Guard, SAR Program Information, http://www.uscg.mil/hq/g-o/g-

opr/sar_program.htm, 2000-2003.

[17] U.S. Military Specification MIL-F-8785C, 5 November 1980.

[18] K. C. Wong, C. Bil, G. Gordon, P.W. Gibbens, “Study of the Unmanned Aerial

Vehicle (UAV) market in Australia”, Aerospace Technology Forum Report,

August 1997.

[19] D. C. Youla, H. A. Jabr, and J. J. Bongiorno, “Modern Weiner-Hopf design of

optimal controllers, part II: The multivariable case”, IEEE Transactions on

Automatic Control, 21: 319-338, 1976.


Recommended