+ All Categories
Home > Documents > [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference...

[American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference...

Date post: 14-Dec-2016
Category:
Upload: tal
View: 212 times
Download: 0 times
Share this document with a friend
17
Cooperative UAV Tracking Under Urban Occlusions and Airspace Limitations Vitaly Shaferman * and Tal Shima ** Technion - Israel Institute of Technology, Haifa, 32000,Israel A centralized approach for multi UAV cooperative motion planning, for tracking a pre- dictable ground moving target in urban environments with airspace limitations, using gim- balled or body fixed sensors, is presented. Automating this task is motivated by the expected reduction in operators’ workload and performance improvement. To ensure fly- able trajectories, adequate performance, and safety, the UAVs’ dynamics, occlusions and airspace constrains must all be incorporated into the problem’s formulation. The solution strategy involves determining visibility, sensor coverage, and restricted regions in the cal- culated horizon using either a priori or operator provided information on the urban terrain and target trajectory. The tracking task is then casted as a centralized optimization motion planning problem, in which the cost function is associated with the UAVs’ positions rela- tive to the visibility and restricted regions, and the target’s position relative to the sensor coverage region. A computationally parsimonious stochastic search method (genetic al- gorithm) is proposed for solving the resulting optimization problem. The algorithm was implemented in a high fidelity simulation test-bed using a visual database of an actual city. The viability of using the algorithm is shown using a Monte Carlo study. I. Introduction The use of unmanned aerial vehicles (UAVs) has increased dramatically in the last two decades both in military and civilian applications. Civilian applications include geological surveying, fire monitoring, and search and rescue missions. Military applications include reconnaissance, providing a communication relay, and conducting search and destroy missions. Their extensive use was mainly promoted to reduce the risk to human life, lower cost, and increase operational capabilities. Several UAV applications require target tracking, which becomes an especially challenging problem when the target is moving in an urban environment and airspace limitations inhibit the UAVs’ possible trajectories. In such a setting the onboard UAV’s sensor line of sight (LOS) to the target might be occluded by the presence of buildings and the UAVs might violate airspace limitations. The operator has to track the target using the UAV’s sensor and plan a trajectory that can be followed by the UAV and not result in target occlusion or airspace limitation breach. The operator’s workload preforming the described mission would therefore be extremely high even for a single UAV, and amount to the mere impossible for a multi UAV scenario. In Ref. 1 a two dimensional scenario of a single observer with speed bounded dynamics tracking a target with occlusions was addressed. For the predictable target case, the acceptable observer locations were marked using a computed visibility polygon, and the dynamic programming approach was used to solve the optimization. The main drawback of the dynamic programming approach is its computational complexity. Evolutionary algorithms (EAs) are well known optimization tools used in many disciplines. 2 They enable efficient search for feasible solutions. The methods involves iteratively manipulating a population called chromosomes, which encode candidate solutions, to obtain a population that includes better solutions. The manipulation is performed by applying evolutionary operators like: selection, crossover, and mutation. Can- didate solution selection is performed by evaluating the fitness of each chromosome in the population. Histor- ically, there were three main types of EAs: genetic algorithms (GA), evolutionary strategies, and evolutionary programming, with GA being the most popular one. * Graduate Student, Department of Aerospace Engineering; [email protected] ** Senior Lecturer, Department of Aerospace Engineering; Senior Member AIAA; [email protected]; This work was supported in part by the government and a Horev fellowship through the Taub foundation. 1 of 17 American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit 18 - 21 August 2008, Honolulu, Hawaii AIAA 2008-7136 Copyright © 2008 by the authors. Published by the American Institute of Aeronautics and Astronautics, Inc., with permission.
Transcript
Page 1: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

Cooperative UAV Tracking Under Urban Occlusions

and Airspace Limitations

Vitaly Shaferman∗ and Tal Shima∗∗

Technion - Israel Institute of Technology, Haifa, 32000,Israel

A centralized approach for multi UAV cooperative motion planning, for tracking a pre-dictable ground moving target in urban environments with airspace limitations, using gim-balled or body fixed sensors, is presented. Automating this task is motivated by theexpected reduction in operators’ workload and performance improvement. To ensure fly-able trajectories, adequate performance, and safety, the UAVs’ dynamics, occlusions andairspace constrains must all be incorporated into the problem’s formulation. The solutionstrategy involves determining visibility, sensor coverage, and restricted regions in the cal-culated horizon using either a priori or operator provided information on the urban terrainand target trajectory. The tracking task is then casted as a centralized optimization motionplanning problem, in which the cost function is associated with the UAVs’ positions rela-tive to the visibility and restricted regions, and the target’s position relative to the sensorcoverage region. A computationally parsimonious stochastic search method (genetic al-gorithm) is proposed for solving the resulting optimization problem. The algorithm wasimplemented in a high fidelity simulation test-bed using a visual database of an actual city.The viability of using the algorithm is shown using a Monte Carlo study.

I. Introduction

The use of unmanned aerial vehicles (UAVs) has increased dramatically in the last two decades both inmilitary and civilian applications. Civilian applications include geological surveying, fire monitoring, andsearch and rescue missions. Military applications include reconnaissance, providing a communication relay,and conducting search and destroy missions. Their extensive use was mainly promoted to reduce the risk tohuman life, lower cost, and increase operational capabilities.

Several UAV applications require target tracking, which becomes an especially challenging problem whenthe target is moving in an urban environment and airspace limitations inhibit the UAVs’ possible trajectories.In such a setting the onboard UAV’s sensor line of sight (LOS) to the target might be occluded by the presenceof buildings and the UAVs might violate airspace limitations. The operator has to track the target usingthe UAV’s sensor and plan a trajectory that can be followed by the UAV and not result in target occlusionor airspace limitation breach. The operator’s workload preforming the described mission would therefore beextremely high even for a single UAV, and amount to the mere impossible for a multi UAV scenario.

In Ref. 1 a two dimensional scenario of a single observer with speed bounded dynamics tracking a targetwith occlusions was addressed. For the predictable target case, the acceptable observer locations weremarked using a computed visibility polygon, and the dynamic programming approach was used to solve theoptimization. The main drawback of the dynamic programming approach is its computational complexity.

Evolutionary algorithms (EAs) are well known optimization tools used in many disciplines.2 They enableefficient search for feasible solutions. The methods involves iteratively manipulating a population calledchromosomes, which encode candidate solutions, to obtain a population that includes better solutions. Themanipulation is performed by applying evolutionary operators like: selection, crossover, and mutation. Can-didate solution selection is performed by evaluating the fitness of each chromosome in the population. Histor-ically, there were three main types of EAs: genetic algorithms (GA), evolutionary strategies, and evolutionaryprogramming, with GA being the most popular one.

∗Graduate Student, Department of Aerospace Engineering; [email protected]∗∗Senior Lecturer, Department of Aerospace Engineering; Senior Member AIAA; [email protected];

This work was supported in part by the government and a Horev fellowship through the Taub foundation.

1 of 17

American Institute of Aeronautics and Astronautics

AIAA Guidance, Navigation and Control Conference and Exhibit18 - 21 August 2008, Honolulu, Hawaii

AIAA 2008-7136

Copyright © 2008 by the authors. Published by the American Institute of Aeronautics and Astronautics, Inc., with permission.

Page 2: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

In Ref. 3 an adaptive evolutionary planner/navigator for mobile ground robots with obstacles was pro-posed. The planner used trajectory nodes coding, and unified off-line planning and on-line planning/navigationin the same evolutionary algorithm. The main drawback of this approach is that the resulting trajectorydoes not account for the dynamic constrains, therefore UAVs having a minimal turn radius and minimumspeed constraints, can’t adequately follow such a trajectory. In Ref. 4 routing of autonomous underwatervehicles (AUVs) through evolutionary programming was considered. The authors used an instruction list ofchanges in the AUV’s speed and heading coding, to plan a trajectory that passes though required points atspecified times, while avoiding fixed threats. A similar coding was used by Ref. 5 for the motion planningproblem with obstacles, by adopting a variable length command list. Such coding can directly account forsome of the UAV’s dynamic constraints by limiting the maximal heading and speed change in every timestep.

In scenarios where target tracking can not be maintained/ensured by a single UAV, two or more UAVsmight be required for the task. Multiple UAVs cooperation can be categorized to centralized and decentral-ized approaches. In the centralized approach6–8 a central control agent (one of the UAVs or a control center)plans the UAVs’ trajectories. While in the decentralized approach9 each UAV plans its own trajectory basedonly on its local information or that communicated by neighboring UAVs, but not based on the global infor-mation available from all UAVs. Each approach, centralized and decentralized, has its respective pros andcons. The centralized approach usually generates better solutions due to the use of global information, whiledecentralized algorithms are usually more computationally parsimonious, scalable, and robust

The main objective of this paper is to present a comprehensive methodology enabling to automatethe cooperative tracking mission of a predictable ground target in an urban environment with airspacelimitations, thus reducing the associated operators’ workload and improving overall mission performance.For this task we propose a centralized GA based motion planning algorithm, that accounts for the UAVs’dynamic constraints. It enables the tracking to be performed with multiple UAVs, carrying gimballed orbody fixed sensors, having preferably different look angles at the target. The remainder of this paper isorganized as follows: In the next section the mathematical formulation is described, followed by the GAmulti UAV tracking planner (GAMUTP) derivation in Sec. III. A simulation study is presented in Sec. IV,followed by concluding remarks.

II. Mathematical Formulation

The mathematical formulation of the problem where multiple UAVs track a ground moving target inan urban terrain with airspace limitations is presented in this section. First, the UAVs’ dynamics andkinematics are discussed. This is followed by a representation of the urban environment occlusions, sensorcoverage regions and restricted regions. Finally, the cost function for the problem is presented.

A. Non-Linear UAV Kinematics and Dynamics

LetU = {1, 2, ..., Nu} (1)

be the set of UAVs performing the cooperative tracking. In Fig. 1 a schematic planar view of the trackinggeometry is shown, where XI , Y I , ZI is a Cartesian inertial reference frame with the ZI axis pointingoutwards. We denote the UAVs and target by the subscripts i ∈ U and T , respectively. XB

i , Y Bi , ZB

i is abody fixed Cartesian reference frame attached to the ith UAV with the origin at the UAV’s center of gravity(CG), Y B

i axis pointing forward, XBi axis passing though right wing and the ZB

i axis pointing upwardaccording to the right hand rule. The speed, normal acceleration, and heading of the UAVs are denotedby Vi, ai, and ψi, respectively. Assuming that the UAVs are flying at a constant altitude and speed, andneglecting wind effects, the UAVs’ kinematics relative to the inertial reference frame, is

xi = Vi sin (ψi) (2a)yi = Vi cos (ψi) (2b)zi = 0 (2c)ψi = ai/Vi (2d)

In addition we assume that the UAVs are equipped with an autopilot system for which the lateralacceleration command uψi ; i ∈ U is the only required input and it is bounded uψi ∈ [−umax

ψi, umax

ψi]. Thus,

2 of 17

American Institute of Aeronautics and Astronautics

Page 3: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

XI

Y

Viψi

yi

yT

xi xT

Y I

OI

X

Y B

i

ai

ri

XB

i

OB

i

Figure 1. Planar view of the tracking geometry.

the UAVs’ dynamics can be represented by the following arbitrary order non-linear equation set

xDi = f(xDi, uψi, t) (3)

whereai = g(xDi, uψi, t) (4)

and xDi is the vector of UAV i ∈ U internal state variables with dim(xDi) = n.We define the state vector of UAV i ∈ U as

xi =[

xi yi zi ψi xDi

]T

(5)

andxi =

[xT

i xTT

]T

(6)

is the state vector associated with a single UAV and the target, where xT = [xT , yT , zT ]T is the target’sposition relative to the inertial reference frame.

The state vector of the entire problem, which includes the states of all the UAVs and that of the targetis therefore

x =[

xT1 xT

2 · · · xTNu

xTT

]T

(7)

B. Urban Environment Occlusions and Restricted Regions

We will now mathematically define the concepts of occlusion, visibility region, visibility polygon, sensorcoverage region, and restricted region.

1. Visibility Region

LetO = {1, 2, ..., No} (8)

be the set of buildings or other objects representing the urban environment. Each element o ∈ O is repre-sented by a polyhedron’s body Bo, therefore

B =No⋃o=1

Bo (9)

3 of 17

American Institute of Aeronautics and Astronautics

Page 4: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

represents all the objects in the modeled urban environment. Let

Xi ={(xi, yi, zi) ∈ R3|zi ≥ 0

}(10)

be the space of all possible position states of the ith UAV relative to the inertial Cartesian reference framepresented in Fig. 1. Therefore, for every possible target location xT and a given urban environment B, thetarget visibility region XV

i (xT ) ⊂ Xi is the subspace for which a LOS exists to the target location xT .Note that XV

i (xT ) is a function of target position and the modeled urban environment B alone. It istherefore the same for all UAVs, and is time dependant for a moving target.

In the previous section we have assumed that the UAVs are flying at constant altitudes. We denote thealtitude of the ith UAV as hi . Let

Xhii = {(xi, yi, zi) ∈ Xi|zi = hi} (11)

be the plane defined using this altitude. Therefore, for every possible target location xT and a given urbanenvironment B, XhiV

i (xT ) ⊂ Xhii is the subspace for which a LOS exists to the target location xT at the

ith UAV’s altitude hi

XhiVi (xT ) = Xhi

i ∩XVi (xT ) (12)

We denote XhiVi (xT ) as the target visibility region, at altitude hi. The ith UAV is within the target visibility

region at a given time t , if Dxi(t) ∈ XhiVi (xT ), where D is a constant matrix

D =[

I3×3 [0]3×(1+n)

](13)

with I representing the identity matrix and [0] a matrix of zeros.Fig. 2 presents a schematic example of the visibility region of a single target at altitude hi. In this figure

UAV#2 is in the visibility region, therefore Dx2(t) ∈ XhiV2 (xT ); and UAV#1 is outside the visibility region,

therefore Dx1(t) /∈ XhiV1 (xT ). For simplification, in the rest of the derivation we will not carry the notation

for the dependency of XhiVi on xT (and consequently possibly on time as well).

Figure 2. Visibility region schematic example.

For given target location, urban terrain occlusion map, and UAV/sensor altitude, XhiVi can be calculated

using a sweep algorithm. Using such an algorithm will result in a visibility polygon for every calculated timet. To allow realtime implementation we compute the visibility polygons at discrete times with intervals of∆T .

4 of 17

American Institute of Aeronautics and Astronautics

Page 5: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

2. Sensor Coverage Region

The target visibility region accounts only for the urban environment occlusions. To enable target trackingwe would also need to verify that the target is within the sensor’s effective range, footprint, and that it isnot masked by the UAV. These questions will be addressed next.

The relative position rBi , between the ith UAV and the target, represented in the body fixed reference

frame of Fig. 1 is

rBi = DI

Bi (xT −Dxi) (14)

where DIBi is the direction cosine matrix (DCM) from the inertial to the ith UAV’s body reference frame.

Note that xi and xT are time dependent, therefore rBi is also time dependent. Let us define the ith UAV’s

body fixed spherical sensor coordinates system (ρ, ϕ, θ)i, with its origin located at the sensor’s position andwhich is aligned with the UAV’s body frame. Assuming that the distance between the UAV’s CG locationand the sensor’s location is negligible relative to the range to the target: ϕiT , the target’s elevation, isthe angle between the LOS and the positive ZB

i axis; θiT , the target’s azimuth, is the angle between theprojection of the LOS on the XB

i Y Bi plane and the Y B

i axis; and ρiT is the range between the UAV and thetarget (see Fig. 3).Then, rS

i , which is the sensor spherical coordinates representation of rBi , can be obtained by

ρiT = ‖rBi ‖2 (15a)

ϕiT = arccos(

rBiz

‖rBi ‖2

)(15b)

θiT = arctan

(rBix

rBiy

)(15c)

where rBi =

[rBix, rB

iy, rBiz

]T and rSi = [ρiT , ϕiT , θiT ]T .

ZBi

Y Bi

rBiz

rBi

T

rBix XB

i

ϕiT θiT

rBiy

OBi

Figure 3. Spherical sensor coordinates

Let us define XTi to be the space of all possible target positions relative to the body fixed reference frame

of the ith UAV represented in the spherical sensor coordinates system

XTi =

{(ρiT , ϕiT , θiT ) ∈ R3| 0 ≤ ρiT < ∞, 0 ≤ ϕiT < π, 0 ≤ θiT < 2π

}(16)

Then, the sensor coverage region Xsensori ⊂ XT

i is a subspace, from which the target could be tracked by theith UAV’s sensor if the urban terrain occlusions were not present. Therefore, the target will be consideredtracked by the ith UAV at a given time t, if the UAV’s position states are within the target visibility regionDxi ∈ XhiV

i (xT ) and the target is within the sensor’s coverage region rSi ∈ Xsensor

i .UAV sensors can be roughly divided into two categories: Gimballed and Body fixed. Gimballed sensors

are usually more complex and enable pointing the sensor to a desired position, with usually minimal effect bythe UAV’s state. Body fixed sensors are usually much simpler and cheaper, but their footprint is determinedby the UAV’s states like pitch and roll angles.

5 of 17

American Institute of Aeronautics and Astronautics

Page 6: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

If the UAV is carrying a gimballed sensor, and its dynamics is much faster than the UAV’s dynamics,then Xsensor

i can be represented as a Cartesian product Xsensori = Ri×Mi, where Ri can receive any value

between the minimal and maximal sensor effective range, and Mi is a subspace representing all the angularpositions the sensor’s footprint can attain, without being masked by the UAV’s body.

Ri ={ρi ∈ R+|ρmin

i ≤ ρi ≤ ρmaxi

}(17a)

Mi ={(ϕi, θi) ∈ R2| 0 ≤ ϕiT < π, 0 ≤ θiT < 2π, no UAV mask

}(17b)

For given sensor performance, installation location and UAV geometry, Mi can be represented by apolygon in (ϕi, θi). Mi can be obtained during the UAV’s design stage, based on solid models or afterproduction by measuring the installed UAV. The target is within the sensor’s coverage region if rS

i ∈ Xsensori .

This requirement can be separated into two necessary conditions

E1rSi ∈ [ρmin

i , ρmaxi ] (18a)

E2rSi ∈ Mi (18b)

where E1 and E2 are constant matrixes

E1 =[

1 0 0], E2 =

[0 1 00 0 1

](19)

When the gimballed sensor is positioned underneath the UAV, it has full coverage of the lower hemisphere.In such a case, if the UAV’s bank and pitch angles are small, no masking from the UAV’s body occurs,resulting in the satisfaction of Eq. (18b). This leaves only the necessary condition presented in Eq. (18a).Note that this is usually the case for most gimballed UAV sensors.

If the UAV is carrying a body fixed sensor the same formulation can be used, where Mi is a subspacerepresenting all the angular positions (ϕi, θi) the sensor’s field of view (FOV) covers, not masked by theUAV’s body. Unlike gimballed sensors for body fixed sensors the necessary condition of Eq. (18b) usuallyhas to be checked, because the sensor’s FOV usually does not cover the entire lower hemisphere and becausethese UAVs tend to be smaller, fly lower and therefore also tend to generate higher roll and pitch angles.

3. Collision Avoidance and Restricted Region

In the operation of aerial vehicles altitude de-confliction can be used to avoid collision between the UAVs.Thus, in contrast to planning problems for multiple ground robots, the trajectory of each UAV can beobtained independently. This reduces considerably the coupling between the trajectories of the UAVs inthe group. However, different altitudes define different visibility polygons. The derivation accounted forthis difference in visibility polygons, but for simplicity we use in our implementation the same visibilitypolygon for all UAVs. This can be justified by assuming that the difference in altitude is small renderingthe difference in visibility polygons negligible. Another possibility is to use for the planning of the entiregroup the polygon obtained for the UAV flying at the lowest altitude, as it is a subset of all the othersXhiV

i ⊆ XhjVj ∀j ∈ U | hi ≤ hj .

We will now define the concept of restricted region. Let

L = {1, 2, ..., Nl} (20)

be the set of airspace limitations imposed on the UAVs. Each element l ∈ L is represented by a polyhedron’sbody Rl, therefore

R =Nl⋃

l=1

Rl (21)

represents all the airspace limitations imposed on the UAVs. Then, the restricted region of the ith UAVgiven the urban terrain B with the airspace limitations R is

XRi = Xi ∩ (B ∪R) (22)

And by confining the ith UAV to the altitude hi we obtain XhiRi which is the UAV’s restricted region in the

given altitudeXhiR

i = Xhii ∩XR

i (23)

which accounts for both the urban environment and airspace limitations.

6 of 17

American Institute of Aeronautics and Astronautics

Page 7: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

C. Cost Function

We will now define the cost function for the tracking problem. We will first define the cost function for asingle UAV, which we will later expand to the multi UAV scenario.

As discussed in the previous subsection, we compute the visibility polygons in intervals of ∆T . Our mainobjectives are to maintain the (xi, yi) position of the UAV within the visibility polygons and maintain therelative position rS

i within the sensor coverage region, while avoiding the restricted region. Therefore, thecost function chosen in this paper is

Ji = a · lf (xi(tM )) +M−1∑

k=0

lk(xi(tk), uψi(tk)) (24)

where tM = M∆T is the calculated horizon and a is non-negative constant. lf (x(tM )) is the loss associatedwith the final state and lk(xi(tk), uψi(tk)) is the loss associated with the state xi and the control commanduψi at time tk = k∆T .

By choosing lf = 0, and

lk(xi(tk), uψi(tk)) =

0 Dxi(tk) ∈ XhiVi , rS

i (tk) ∈ Xsensori , Dxi(tk) 6∈ XhiR

i

1 Dxi(tk) 6∈ XhiVi or rS

i (tk) 6∈ Xsensori , Dxi(tk) 6∈ XhiR

i

WR Dxi(tk) ∈ XhiRi

(25)

where D is a constant matrixD =

[I3×3 [0]3×(n+4)

](26)

and XhiVi is calculated for tk, we impose a cost function that measures the amount of time frames for which

the target is not tracked by the ith UAV, and the amount of time frames weighted by WR for which the ith

UAV is within the restricted region. By choosing WR →∞ we can impose a solution that does not penetratethe restricted regions. By defining lf in a similar manner, we can impose a final location on the UAV, whileavoiding the restricted region.

Let us now expand the cost function proposed in Eq. (24) to a multi UAV scenario. In such a setting,we would like the target to be tracked by at least one UAV, while tracking from multiple UAVs is preferredto increase the solution robustness and to verify that none of the UAVs diverge even when good trackingperformance of the other UAVs is attained. Let Tk(x(tk)) ∈ {0, 1} be a binary decision variable that is 0 ifat least one UAV is tracking the target at time tk = k∆T and 1 otherwise

Tk(x(tk)) =

{0 ∃ i | Dxi(tk) ∈ XhiV

i , rSi (tk) ∈ Xsensor

i

1 else(27)

We can now expand Eq. (24) in the following manner

J =M−1∑

k=0

Tk + bTM + c

Nu∑

i=1

Ji (28)

This cost has to be minimized by the group under the kinematic constraints of the UAVs given in Eq. (2).Note that the individual cost for every UAV is weighted by a non-negative number, c, and b is a non-negativeweight on Tk at the final time tk = M∆T . Increasing c will result in solutions in which the individual trackingperformance of each UAV will improve, on the expense of global tracking performance and vise versa.

III. GA Multi UAV Tracking Planner

Multi UAV tracking in an urban environment was mathematically formulated in the previous sectionas a very complex optimization problem. The need to maintain the UAVs’ position states in the visibilitypolygons, and the relative positions within the sensors’ coverage regions, while avoiding restricted regions,and accounting for the dynamic constraints of the UAVs, results with a large number of constraints makingany attempt to analytically solve the problem using optimal control tools impractical. Due to the need

7 of 17

American Institute of Aeronautics and Astronautics

Page 8: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

for realtime implementation, the planning algorithm should have the following desirable attributes: quickfeasible solution and monotonically improving solution quality over runtime.

As presented in Sec. I, EAs are well known optimization tools, and have been shown suitable for solvingmotion planning problems. In this section we will present a GA multi UAV tracking planner, which has thedesirable characteristic stated above.

A. Encoding

An important part of solving such a problem using a GA is to select the appropriate chromosome encoding.Due to the need to account for the dynamic constraints of the UAVs, the candidate solution for each UAVis represented by a string of discrete acceleration commands, of the form presented in Fig. 4, in which eachcommand uk

ψirepresents a constant input to the UAV’s autopilot system for the time interval of t ∈ [tk, tk+1).

Each such chromosome representation of the solution is composed of an ordered set GM of M + 1 geneswhere

GM = {g0, g1, ..., gM} (29)

By limiting ukψi

to the closed set ukψi∈ [−umax

ψi, umax

ψi], we can guarantee that any candidate solution will

uphold the dynamic constraints of the UAV as presented in Sec. II. A. The possible values of ukψi

can either

be any continuous value in the closed set ukψi∈ [−umax

ψi, umax

ψi] , or can be chosen from a subset of those values

ukψi∈

{(uψi)

1, (uψi)2, ..., (uψi)

q}⊂ [−umax

ψi, umax

ψi]. In this paper we have chosen to use the former option.

UAV Team

Single UAV

t0

... ... ...u0

ψ1u

1

ψ1uk

ψ1uM

ψ1

tk

... ... ...u0

ψ2u

1

ψ2uk

ψ2uM

ψ2

t1

......

......

......

...

... ... ...u0

ψNu

u1

ψNu

uk

ψNu

uM

ψNu

tM

UAV No. i uM

ψiuk

ψiu

1

ψiu

0

ψi.........

UAV No. 2

UAV No. 1

UAV No. Nu

Figure 4. Control input encoding

Thus far we have considered the solution encoding of a single UAV. Let us now expand the proposedencoding to a multi UAV setting. We propose to combine the encoding for all UAVs to one large chromosomeand perform the genetic operators on that chromosome, resulting in a single population containing thesolution for the entire team. The Chromosome has a matrix shape in which every row represents thesolution for one UAV and every column represents the same time frame for all UAVs. Fig. 4 schematicallypresents this structure.

B. Candidate Solutions Evaluation

The fitness f of each of the solutions, coded in the chromosomes presented in the previous section, will bebased on computing the cost function of Eq. (28) where

f = 1/J (30)

Calculating the value of Eq. (28) for each chromosome requires the value of each UAV’s state xi, which canbe obtained by integrating Eqs. (2), (3), and (4), using the acceleration commands coded in the chromosomes.Such an integration can be performed numerically for any UAV dynamics using numerical ordinary differentialequation (ODE) solvers, like the Runge-Kutta method. Note that although Eqs. (2), (3), and (4) are

8 of 17

American Institute of Aeronautics and Astronautics

Page 9: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

continuous, the values of the UAV state xi are only needed at discrete times tk = k∆T . To simplify thesolution, an ideal dynamics Dubins10 car model type UAV was considered in this paper, for which Eq. (4)degenerates to

ai = g(xDi, uψi, t) = uψi (31)

Once xi has been calculated, the cost function of Eq. (28) can be evaluated by examining whether,for each time frame in the calculated horizon : 1) Dxi ∈ XhiV

i ; 2) Dxi 6∈ XhiRi ; 3) E2rS

i ∈ Mi; 4)E1rS

i ∈ [ρmini , ρmax

i ]. Conditions 1-3 require checking if a point lies within a polygon. The point in a polygon(PIP) is a well known problem in computational geometry11. The problem is to find out whether a givenpoint in the plane lies inside a polygon. Many algorithms for this problem appear in the literature, likethe winding number or crossing number algorithms11. In the crossing number algorithm for example, thenumber of times a ray starting from the point intersects the edges of the polygon is counted. The point isinside the polygon iff the number is odd. The algorithm complexity is O(Np), where Np is the number ofpolygon edges.

Remarks : 1) The visibility polygons for an entire scenario can be calculated in O(NpM) time, whereM is the number of time frames in the calculated horizon. These polygons are calculated once for the targettrajectory, before the GA is run. One option to reduce the calculation time is to compute visibility polygonsoff-line for some sampled target position resolution, and store them in a database. Extracting the polygonsfrom the database can be done in realtime, based on the expected target location. 2) Unlike the visibilitypolygon, the restricted region might be comprised of a few polygons, each emanating from a different airspacelimitation. To reduce the computation load the restricted regions should be organized in a database whichenables fast sorting of which restricted regions apply according to the current UAV location. Thus, limitingthe evaluation only to restricted regions in the UAV’s vicinity and eliminating the need to check all therestricted regions.

C. Reproduction Process

Our algorithm is initialized with Ns randomly generated chromosomes and we maintain a fixed sized popu-lation throughout the process. Off-line, reproducing new generations of solutions can be repeated until somestopping criterion is met, e.g. the fitness of the best chromosome hasn’t improved more than 5% from theprevious iteration. For an on-line implementation the algorithm can be run only for a given allotted time. Inthis study the population has been progressed for a given number of generations, denoted Ng. For creatinga new population of solutions we employ the genetic operators: selection, crossover, mutation, and elitism.

1. Selection

In this stage two parent chromosomes are selected based on their fitness. For the selection we employ theroulette wheel method.

LetC = {c1, c2, ..., cNs} (32)

be the set of chromosomes. Using the mapping of Eq. (28) and Eq. (30) let

F = {f1, f2, ...fNs} (33)

be the set of corresponding fitness of the chromosomes. These sets do not have to be ordered. We nowcalculate

Fs =Ns∑

χ=1

fχ (34)

and define the setFc = {Fc1, F c2, .., F cNs} (35)

where

Fcξ =ξ∑

χ=1

fχ ; ξ = 1, 2, ..., Ns (36)

Note that Fc1 = f1 and FcNs = Fs.

9 of 17

American Institute of Aeronautics and Astronautics

Page 10: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

We then generate a uniformly distributed random number µ ∼ U(0, Fs) and select as the first parent thechromosome that satisfies

parent = argcξ∈C

min(Fcξ − µ ≥ 0) (37)

and repeat the process for the second parent.

2. Crossover

We apply the crossover operators with a probability denoted as pc. The probability that the offsprings willbe exact replicas of their parents is bounded from below by (1 − pc) since there is a non zero probabilitythat identical parents will be chosen. In this study three types of single point crossover methods have beenchosen, and the methods are schematically illustrated in Fig. 5.

����������������������������

����������������������������

����������������������������������������

����������������������������������������

Crossover Row

Crossover RowPoint

Turn

Full Row

i Crossover PointCrossover Pointi

j

j

uMψNu

uMψ1

uMψ2

...

ukψ2

u1

ψ2u0

ψ2.........

ukψNu

u1

ψNu

u0

ψNu

.........

......

......

......

ukψ1

u1

ψ1u0

ψ1............ ... ...u0

ψ1u1

ψ1ukψ1

......

......

......

... ... ...u0

ψNu

u1

ψNu

ukψNu

... ... ...u0

ψ2u1

ψ2ukψ2

ukψ2

u1

ψ2u0

ψ2.........

ukψNu

u1

ψNu

u0

ψNu

.........

......

......

......

ukψ1

u1

ψ1u0

ψ1.........

uMψ2

uMψ1

uMψNu

...

uMψ2

uMψ1

ukψ2

u1

ψ2u0

ψ2.........

ukψNu

u1

ψNu

u0

ψNu

.........

......

......

......

ukψ1

u1

ψ1u0

ψ1.........

uMψNu

...

... ... ...u0

ψ1u1

ψ1ukψ1

......

......

......

... ... ...u0

ψNu

u1

ψNu

ukψNu

... ... ...u0

ψ2u1

ψ2ukψ2

...

uMψ2

uMψ1

uMψNu

... ... ...u0

ψ1u1

ψ1ukψ1

......

......

......

... ... ...u0

ψNu

u1

ψNu

ukψNu

... ... ...u0

ψ2u1

ψ2ukψ2

...

uMψ2

uMψ1

uMψNu

uMψNu

uMψ1

uMψ2

...

Figure 5. Crossover operators

In the first method, applied with probability pcf , and denoted full row crossover, a column i is selectedrandomly based on a uniform distribution. When applying this operator, the first child solution consists ofthe first gs = iNu genes (i genes from each row) from the first parent and (M + 1)Nu − gs genes from thesecond parent; and vice versa for the second child.

In the second method, applied with probability pt, and denoted turn crossover, a column i, a row jand an acceleration command uψi ∈ [−umax

ψi, umax

ψi] are selected randomly from uniform distributions. When

applying this operator the genes in all rows except the jth row are passed directly from the first parent tothe first child and similarly for the second child. The last gs = M + 1 − i genes of the first child and thefirst gs = i genes of the second child in the jth row are replaced with a constant acceleration command uψi,the last gs = M + 1− i genes of the second child and the first gs = i genes of the first child are taken fromthe first parent. This operator manipulates a single UAV in both parents and is a blend of a crossover anda mutation operator.

In the last method, applied with probability (1− pcf − pt), and denoted point crossover, both a columni and a row j are selected randomly based on uniform distributions. Applying this operator is equivalent tojoining all the UAVs coding of each parent to a string, in which the first child solution consists of the firstgs = (j−1)(M +1)+ i genes from the first parent and Nu(M +1)− gs genes from the second parent strings;and vice versa for the second child.

10 of 17

American Institute of Aeronautics and Astronautics

Page 11: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

Importantly, all crossover operators produce feasible solutions and there is no need of chromosome repairs.Note that the methods have very different physical meanings. The full row crossover operator replaces thetime history of all the UAVs in the candidate child solution from the (i+1)th time frame, the turn crossoveroperator changes the time history of a single UAV and leaves the rest of the UAVs unchanged, while thepoint crossover operator changes the time history of one UAV, while possibly taking complete trajectoriesof other UAVs from other candidate solutions.

3. Mutation

The mutation operator is applied with a probability pm to each gene of the chromosome. We mutate thegene by randomly selecting a new acceleration command value uk

ψi∈ [−umax

ψi, umax

ψi]. The application of this

operator prevents the algorithm from getting trapped in a local minimum of the problem, and from onesolution to dominate the entire population.

4. Elitism

We apply this operator in order to keep the best solutions from each generation of solutions. We keep thebest Ne chromosomes from the previous generation and the rest of the new chromosomes (Ns − Ne) areobtained by repeatedly producing children, by the methods described above, until the entire population isfilled.

Remark: One of the time consuming parts of the algorithm is calculating xi ∀ i ∈ U . Therefore, when-ever the first section of each row is identical to one of the parents then there is no need for re-computing xi

and the associated part of the cost Ji for this section. This can reduce the computation time by approximatelyhalf.

IV. Simulation Study

A simulation study of the GAMUTP’s performance is offered in this section. The simulation was per-formed, using a high fidelity graphics software. We will first present the simulation environment, followedby a presentation of the test scenario. We will then present a sample run and analyze the performance ofthe proposed planner using a Monte Carlo study.

A. Simulation Environment

We utilized the graphics capabilities of a software named Tri-Malat. This C++ application combines sen-sory images from three sensors (payloads) and includes three video channels and a map/ortho view. Theapplication is based on VegaPrime which is a commercial-off-the-shelf tool available for the creation anddeployment of visual simulations. For the terrain it uses the data base of the city of Tel Aviv, Israel. Thecomputer used was an Intel 2.0 GHZ dual core 2 with 2 GB RAM utilizing an NVIDEA GeForce Go 7600graphic card.

The GAMUTP was implemented in Matlab and compiled to a dll using the Matlab compiler toolbox.The UAVs’ motion planning using the GAMUTP is initiated by the operator in the Tri-Malat environment.Based on the operator inputs, the Tri-Malat software calculates the predicted visibility polygons in thecalculated horizon and passes the polygons and UAVs’ initial states to the planner. The planner returnsthe planned trajectory, autopilot commands, tracking strategy, and predicted tracking performance for allthe tasked UAVs. The motion plan is then implemented in the Tri-Malat environment, freeing the operatorfrom the path planing mission.

B. Test Scenario

The test scenario is 120 sec long, and consists of a target moving at approximately 15 m/sec. Fig. 6 presentsthe target trajectory on an orthophoto, where the dots represent 10 sec intervals. The target is tracked bymultiple homogeneous UAVs flying above the urban environment at a constant speed of Vi and a constantaltitude of hi. Three square 400 × 400 m restricted regions inhibit the UAVs at their flight altitude, withcenters situated at (−300,−300), (−1100, 400) and (−1100,−800), two of which can be seen in Fig. 6 markedas darker areas on the orthophoto.

11 of 17

American Institute of Aeronautics and Astronautics

Page 12: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

Figure 6. A map of the test scenarios

The UAVs’ are carrying gimballed sensors situated underneath the UAV with a maximal range of 3000 mand with no UAV body masking. The UAVs’ positions are initialized at a distance Ro in each axis from theinitial target location. The visibility polygons are computed at intervals of ∆T , and each polygon consistsof Np nodes. The maximal acceleration command can be derived from umax

ψi= V 2

i /Rmin. The weights ofEq. (28) and Eq. (24) were chosen as a = b = c = 1, and lf = lk and equals to Eq. (25). The parametersused for the simulation and the GA are summarized in Table 1, where the values marked with brackets arethe default ones.

Table 1. Simulation Parameters

GA Scenario

Ns ∈ {10, 20, (40), 80} Vi = 30 m/secNe = 4 hi = 800 m

pc = 0.9 Rmin ∈ {100, (200), 400} m

pcf = 0.5 Nu ∈ {1, (2), 3, 4}pt ∈ {0, (0.2)} Ro ∈ [0, 1500] m

pm = 0.01 ∆T = 1 sec

Ng = 100 Np = 18

Fig. 7 present the planned trajectories of two UAVs and a ground moving target in the described scenario.The circles and squares on the UAVs’ trajectories, indicate loss of LOS of UAV#1 and UAV#2 respectively,signifying the UAVs were outside the visibility polygons at the marked locations. The circles and squaresare also marked on the target trajectory, indicating the target’s location when the loss of LOS transpired.

Note that for the presented sample run, the first UAV has lost LOS to the target in 10 time frames out of120, mainly due to initiation in a diverging direction far from the target, while the second UAV lost LOS tothe target in 5 time frames. The loss of LOS of the two UAVs transpired at different time frames resultingin perfect team tracking performance, while avoiding the restricted regions.

12 of 17

American Institute of Aeronautics and Astronautics

Page 13: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

−1400 −1200 −1000 −800 −600 −400 −200 0 200

−600

−400

−200

0

200

400

600

800

1000

X (m)

Y (

m)

TargetUAV 1UAV 2No Los 1No Los 2Restricted

Start

Figure 7. Sample run of 2 UAVs tracking a ground target

C. Monte Carlo Simulation

A Monte Carlo study, consisting of sets of 200 runs, is used in this section to evaluate the performance of theGAMUTP. For every run the position and heading of the UAVs were selected from a uniform distribution,and only positions that were within the first visibility polygon and at a distance grater than Rmin from therestricted regions were selected. The algorithm was then run for the test scenario presented in the previoussection. The results are presented as a function of solutions evaluated, to enable comparisons to populationand non population based methods. Each figure in the study presents the ensemble averages of the totalcost (Eq. (28)) and the team’s tracking cost (Eq. (38)).

[Team tracking (%)] =100

M + 1

M∑

k=0

Tk (38)

Fig. 8 compares between the GAMUTP with two possible values of pt and a random algorithm, using asimilar encoding. The random algorithm generated acceleration commands drawn from a uniform distribu-tion for each candidate solution, and maintained the best solution. The random algorithm performed poorlycompared the the GAMUTP, with an expected cost of E(J) = 156 after 4000 evaluated solutions, versusE(J) = 45 for the GAMUTP, with pt = 0.2. It is also evident that pt = 0, yields substantially higher totaland team tracking costs when compared to pt = 0.2, indicating that the turn crossover operator has vitaleffect on the planner’s performance. The expected value of the team’s tracking cost is approximately 4.5%for these parameters. The expected value of the cost converged to within 5% of its final value after approx-imately 2100 evaluated solutions, which is approximately 53 iterations, for a 40 chromosome population.The computation required 4.5 sec to complete. The expected value of the team’s tracking cost convergedto within 5% of its final value after approximately 1200 evaluated solutions taking 2.6 sec. Although thesecomputation times may constitute realtime performance even when implemented in Matlab (as the scenarioduration is 120sec), it is expected that a C/C++ implementation will further reduce the computational timeby at least an order of magnitude.

Fig. 9 presents the GAMUTP performance for a multi UAV scenario. As expected the total cost increaseswith the number of UAVs, due to the summation of all individual UAV costs. On the other hand, the expectedvalue of the team’s tracking cost decreases, to approximately 2.5% and 1.5% for a 3 and 4 UAV tracking

13 of 17

American Institute of Aeronautics and Astronautics

Page 14: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

0 500 1000 1500 2000 2500 3000 3500 40000

100

200

300

E(J

)

Nu=2, V

i=30 m/s, R

min=200m,

GA : pm

=0.01, pc=0.9, N

s=40

0 500 1000 1500 2000 2500 3000 3500 40000

20

40

60E

(Tea

m t

rack

ing

(%

) )

Solutions evaluated

RandomGAMUTP, p

cf=0.5, p

t=0.2

GAMUTP, pcf

=0.5, pt=0

Figure 8. GAMUTP and Random performance

teams respectively. It is evident that the benefit of adding a fourth UAV to the team, for the trackingperformance alone, is relatively small, although other benefits like robustness can still be gained. Althoughthe Tri-Malat simulation can only currently accommodate three UAVs, a four UAV scenario was run in thisMonte Carlo simulation in the planner alone, which is not limited by this restriction. Note that the algorithmmaintains similar convergence properties for a multi UAV scenario with a moderate increase in the numberof needed evaluations, due to the increased search space. This scalability property is very important for reallife implementation of such an algorithm. Note that the computational time is linearly dependant on thenumber of UAVs (Nu) and the number of evaluated solutions.

Fig. 10 presents the algorithm’s sensitivity to the population size Ns for a two UAV tracking team.When the number of evaluations is lower than 1900, a population size of 20 yields better performance thana population size of 40. While, for a higher number of evaluations a population size of 40 yields betterexpected value cost. It is expected that increasing the population size will eventually yield convergence tobetter solutions as it increases the search space, therefore a population size of 80 will eventually outperformthe 40 member population size. The best tradeoff between run time and performance, in this case, was foundto be Ns = 40.

Fig. 11 analyzes the sensitivity to the UAVs’ minimal turn radius. As expected the team trackingperformance degrades as the minimal turn radius increases, but the performance is still good even whenthe minimal turn radius is increased to Rmin = 400 m. The team cooperation compensates for the higherminimal turn radius in this case.

V. Conclusions

A centralized approach for multi UAV motion planning, for tracking a predictable ground moving targetin urban environments was presented. In the investigated problem multiple UAVs, carrying gimballed orbody fixed sensors, and inhibited by airspace limitations cooperate in performing the tracking task. It wasshown that the proposed solution can automate the task in realtime, thus reducing considerably operators’workload in such real-life problems.

Visibility polygons and restricted regions at a given altitude, in which the UAV must remain, can becalculated for a-priori information about the urban terrain and predicted target trajectory. Sensor coverageregions can also be calculated based on the UAV’s state, geometry and sensor performance. Using theabove, UAV trajectories can be formed that enable target tracking, while avoiding restricted regions, utilizing

14 of 17

American Institute of Aeronautics and Astronautics

Page 15: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

0 500 1000 1500 2000 2500 3000 3500 40000

100

200

300

400

E(J

)

0 500 1000 1500 2000 2500 3000 3500 40000

10

20

30

40

50

Vi=30 m/s, R

min=200m,

GA : pm

=0.01, pc=0.9, p

cf=0.5, p

t=0.2, N

s=40

E(T

eam

tra

ckin

g (

%))

Solutions evaluated

Nu=4

Nu=3

Nu=2

Nu=1

Figure 9. GAMUTP sensitivity to the number of tracking UAVs

0 500 1000 1500 2000 2500 3000 3500 40000

50

100

150

200

E(J

)

0 500 1000 1500 2000 2500 3000 3500 40000

10

20

30

40

Nu=2, V

i=30 m/s, R

min=200m,

GA :pm

=0.01, pc=0.9, p

cf=0.5, p

t=0.2

E(T

eam

tra

ckin

g (

%))

Solutions evaluated

Ns = 10

Ns = 20

Ns = 40

Ns = 80

Figure 10. GAMUTP sensitivity to population size

15 of 17

American Institute of Aeronautics and Astronautics

Page 16: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

0 500 1000 1500 2000 2500 3000 3500 40000

50

100

150

200

250

E(J

)

0 500 1000 1500 2000 2500 3000 3500 40000

10

20

30

40

50

Nu=2, V

i=30 m/s,

GA :pm

=0.01, pc=0.9, p

cf=0.5, p

t=0.2, N

s=40

E(T

eam

Tra

ckin

g (

%))

Solutions evaluated

Rmin

=100 m

Rmin

=200 m

Rmin

=400 m

Figure 11. GAMUTP sensitivity to minimal turn radius

cooperation between the UAVs to minimize the duration the target is not tracked.To ensure flyable trajectories the path planning for each UAV must account for its dynamic constraints.

The problem is computationally intractable for real-time solution using methods such as dynamic program-ming. To provide an implementable solution stochastic search methods such as genetic algorithms can beused. Such an algorithm was derived and implemented in a high fidelity simulation test-bed using a visualdatabase of an actual city. It was shown that the algorithm is scalable and can be applied to large sizedproblems.

VI. Acknowledgments

The authors would like to thank Mr. Jacob Silbiger and his team at Synergy Ltd. for helpful discussionsand help in integrating our algorithm with their Tri-Malat simulation environment.

References

1La Valle, M. S., Gonzalez Banos, H. H., Becker, C., and Latombe, C. J., “Motion Strategies for Maintaining Visibilityof a Moving Target,” In Proc. of the International Conference on Robotics and Automation, IEEE, Piscataway, NJ, 1997, pp.731–736.

2Spall, C. J., Introduction to Stochastic Search and Optimization, Wiley-Interscience, Hoboken, New Jersey, 2003.3Xiao, J., Michalewicz, Z., Zhang, L., and Trojanowski, K., “Adaptive Evolutionary Planner/Navigator for Mobile

Robots,” IEEE Transactions on Evolutionary Computation, Vol. 1, No. 1, 1997, pp. 18–28.4Fogel, B. D. and Fogel, J. L., “Optimal Routing of Multiple Autonomous Under water Vehicles through Evolutionary

Programming,” In Proc. of the 1990 Symposium on Autonomous Underwater Vehicle Technology, IEEE, Piscataway, NJ, 1990,pp. 44–47.

5Capozzi, J. B., Evolution-Based Path Planning and Management for Autonomous Vehicles, Ph.D. thesis, University ofWashington, Seattle, WA, 2001.

6Shima, T., Rasmussen, J. S., Sparks, G. A., and Passino, M. K., “Multiple Task Assignments for Cooperating UninhabitedAerial Vehicles Using Genetic Algorithms,” Computers and Operations Research, Vol. 33, No. 11, 2005, pp. 3252–3269.

7Rasmussen, J. S. and Shima, T., “Tree Search for Assigning Cooperating UAVs to Multiple Tasks,” International Journalof Robust and Nonlinear Control , Vol. 18, No. 2, 2008, pp. 135–153.

8Shima, T., Rasmussen, S., and Gross, D., “Assigning Micro UAVs to Task Tours in an Urban Terrain,” IEEE Transactionson Control System Technology, Vol. 15, No. 4, 2007, pp. 601–612.

9Murray, M. R., “Recent Research in Cooperative Control of Multivehicle Systems,” ASME Journal of Dynamic Systems,Measurement, and Control , Vol. 129, No. 5, 2007, pp. 571–583.

16 of 17

American Institute of Aeronautics and Astronautics

Page 17: [American Institute of Aeronautics and Astronautics AIAA Guidance, Navigation and Control Conference and Exhibit - Honolulu, Hawaii ()] AIAA Guidance, Navigation and Control Conference

10Dubins, L., “On Curves of Minimal Length With a Constraint on Average Curvature, and With Prescribed Initial andTerminal Position,” American Journal of Math, Vol. 79, No. 3, 1957, pp. 497–516.

11Goodman, E. J. and O’Rourke, J., Handbook of Discrete and Computational Geometry, CRC Press, Boca Raton, N.Y.,1997.

17 of 17

American Institute of Aeronautics and Astronautics


Recommended