+ All Categories
Home > Documents > Tree search algorithm for assigning cooperating UAVs to multiple tasks

Tree search algorithm for assigning cooperating UAVs to multiple tasks

Date post: 13-Nov-2023
Category:
Upload: independent
View: 0 times
Download: 0 times
Share this document with a friend
19
INTERNATIONAL JOURNAL OF ROBUST AND NONLINEAR CONTROL Int. J. Robust Nonlinear Control 2008; 18:135–153 Published online 13 August 2007 in Wiley InterScience (www.interscience.wiley.com). DOI: 10.1002/rnc.1257 Tree search algorithm for assigning cooperating UAVs to multiple tasks Steven J. Rasmussen 1 and Tal Shima 2, , 1 Control Science Center of Excellence, Air Force Research Laboratory, Bldg. 146, 2210 Eighth St., Wright-Patterson AFB, OH 45433, U.S.A. 2 Department of Aerospace Engineering, Technion—Israel Institute of Technology, Haifa 32000, Israel SUMMARY This paper describes a tree search algorithm for assigning cooperating homogeneous uninhabited aerial vehicles to multiple tasks. The combinatorial optimization problem is posed in the form of a decision tree, the structure of which enforces the required group coordination and precedence for cooperatively performing the multiple tasks. For path planning, a Dubin’s car model is used so that the vehicles’ constraint, of minimum turning radius, is taken into account. Due to the prohibitive computational complexity of the problem, exhaustive enumeration of all the assignments encoded in the tree is not feasible. The proposed optimization algorithm is initialized by a best-first search and candidate optimal solutions serve as a monotonically decreasing upper bound for the assignment cost. Euclidean distances are used for estimating the path length encoded in branches of the tree that have not yet been evaluated by the computationally intensive Dubin’s optimization subroutine. This provides a lower bound for the cost of unevaluated assignments. We apply these upper and lower bounding procedures iteratively on active subsets within the feasible set, enabling efficient pruning of the solution tree. Using Monte Carlo simulations, the performance of the search algorithm is analyzed for two different cost functions and different limits on the vehicles’ minimum turn radius. It is shown that the selection of the cost function and the limit have a considerable effect on the level of cooperation between the vehicles. The proposed deterministic search method can be applied on line to different sized problems. For small-sized problems, it provides the optimal solution. For large-sized problems, it provides an immediate feasible solution that improves over the algorithm’s run time. When the proposed method is applied off line, it can be used to obtain the optimal solution, which can be used to evaluate the performance of other sub-optimal search methods. Copyright 2007 John Wiley & Sons, Ltd. Received 15 September 2006; Revised 30 May 2007; Accepted 6 June 2007 KEY WORDS: tree search; task assignment; multiple tasks; cooperating agents; uninhabited aerial vehicles Correspondence to: Tal Shima, Department of Aerospace Engineering, Technion—Israel Institute of Technology, Haifa 32000, Israel. E-mail: [email protected] Contract/grant sponsor: Control Science Center of Excellence, AFRL, Wright-Patterson AFB Contract/grant sponsor: Taub Foundation Contract/grant sponsor: Bernard M. Gordon Center for Systems Engineering Copyright 2007 John Wiley & Sons, Ltd.
Transcript

INTERNATIONAL JOURNAL OF ROBUST AND NONLINEAR CONTROLInt. J. Robust Nonlinear Control 2008; 18:135–153Published online 13 August 2007 in Wiley InterScience (www.interscience.wiley.com). DOI: 10.1002/rnc.1257

Tree search algorithm for assigning cooperating UAVsto multiple tasks

Steven J. Rasmussen1 and Tal Shima2,∗,†

1Control Science Center of Excellence, Air Force Research Laboratory, Bldg. 146, 2210 Eighth St.,Wright-Patterson AFB, OH 45433, U.S.A.

2Department of Aerospace Engineering, Technion—Israel Institute of Technology, Haifa 32000, Israel

SUMMARY

This paper describes a tree search algorithm for assigning cooperating homogeneous uninhabited aerialvehicles to multiple tasks. The combinatorial optimization problem is posed in the form of a decisiontree, the structure of which enforces the required group coordination and precedence for cooperativelyperforming the multiple tasks. For path planning, a Dubin’s car model is used so that the vehicles’constraint, of minimum turning radius, is taken into account. Due to the prohibitive computationalcomplexity of the problem, exhaustive enumeration of all the assignments encoded in the tree is notfeasible. The proposed optimization algorithm is initialized by a best-first search and candidate optimalsolutions serve as a monotonically decreasing upper bound for the assignment cost. Euclidean distancesare used for estimating the path length encoded in branches of the tree that have not yet been evaluatedby the computationally intensive Dubin’s optimization subroutine. This provides a lower bound for thecost of unevaluated assignments. We apply these upper and lower bounding procedures iteratively onactive subsets within the feasible set, enabling efficient pruning of the solution tree. Using Monte Carlosimulations, the performance of the search algorithm is analyzed for two different cost functions anddifferent limits on the vehicles’ minimum turn radius. It is shown that the selection of the cost functionand the limit have a considerable effect on the level of cooperation between the vehicles. The proposeddeterministic search method can be applied on line to different sized problems. For small-sized problems,it provides the optimal solution. For large-sized problems, it provides an immediate feasible solution thatimproves over the algorithm’s run time. When the proposed method is applied off line, it can be used toobtain the optimal solution, which can be used to evaluate the performance of other sub-optimal searchmethods. Copyright q 2007 John Wiley & Sons, Ltd.

Received 15 September 2006; Revised 30 May 2007; Accepted 6 June 2007

KEY WORDS: tree search; task assignment; multiple tasks; cooperating agents; uninhabited aerial vehicles

∗Correspondence to: Tal Shima, Department of Aerospace Engineering, Technion—Israel Institute of Technology,Haifa 32000, Israel.

†E-mail: [email protected]

Contract/grant sponsor: Control Science Center of Excellence, AFRL, Wright-Patterson AFBContract/grant sponsor: Taub FoundationContract/grant sponsor: Bernard M. Gordon Center for Systems Engineering

Copyright q 2007 John Wiley & Sons, Ltd.

136 S. J. RASMUSSEN AND T. SHIMA

1. INTRODUCTION

The use of unmanned vehicles for various military and civilian missions in the air, sea, space, andon the ground, has received growing attention in the last decade. Apart from the obvious advantageof not placing human life in harm’s way, the lack of an on-board human operator enables significantweight savings, lower costs, and longer endurance. Once unmanned vehicles have the capabilityto perform missions with a high degree of autonomy it will be possible to employ them in teams,presenting an opportunity for new operational paradigms. If the vehicles are working together toachieve a common objective, then they are considered cooperative. The main motivation for teamcooperation stems from the possible synergy, as the group performance is expected to exceed thesum of the performance of the individual unmanned vehicles. If the unmanned vehicles are unableto cooperate autonomously with each other in online planning and execution of the mission, theneither group autonomy will be traded for high levels of manned intervention or more vehicles willbe required to perform the mission. In this paper, we concentrate on the cooperative assignmentproblem associated with the autonomous operation of a group of unmanned aerial vehicles (UAVs)against multiple stationary ground targets.

Important military missions that have been posed in recent years are suppression of enemy airdefenses and combat intelligence surveillance and reconnaissance [1]. While cooperation in thesetypes of problems, of performing multiple tasks on multiple targets, is desirable, it can be verycomplicated to implement. The cooperative decision and control algorithms, that must be solvedin real time, need to take into account the task coordination and precedence requirements as wellas assign flyable trajectories to the participating UAVs.

In the context of team decision and control, there are two general approaches: (1) agree onthe data or (2) agree on the plan. The second approach is preferable when there is a lot of dataand communications, but the plan is straightforward. The first approach is preferable when theamount of data is low, but the plan is more complex due to high task coupling, for example. If allthe team members have the same data, the same objectives, and are running the same algorithms,then the resulting plans/assignments are identical and coordination is ensured. This method isalso sometimes referred to as implicit coordination because the resulting plans are not explicitlyexchanged. Since each member has all the necessary data, the solution algorithm is centralized,but computed redundantly by all vehicles in the group.

Emerging centralized algorithms of different classes have been proposed for solving such prob-lems involving integer decision variables and continuous controllers. These algorithms are basedon customized combinatorial optimization methods including: mixed integer linear programming(MILP) [2, 3], the capacitated transhipment network solver [4], and the iterative capacitated tran-shipment network solver [5].

Due to the special characteristics of the problem and the requirement for a tractable solution,all these proposed algorithms basically decouple the problem of task assignment from that oftrajectory optimization, resulting with a suboptimal solution. For example, the MILP algorithm of[2] uses Euclidean distances instead of computing flyable trajectories; while that of [3] optimizesthe path planning only for one task at a time and thus the resulting trajectories are only piecewiseoptimal. The single task assignment algorithm [4] is only optimal for the current tasks and does nottake into account the tasks that will be required when the current tasks are completed. Althoughiterations on the single task assignment algorithm (that utilize in essence a greedy solver) [6]provide a solution to the multiple task assignment requirement, the approach is heuristic in natureand therefore optimality is not achieved. Also note that for most problems of realistic complexity,

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 137

involving more than a handful of vehicles and targets, the algorithms in References [2, 3] take along time to execute.

In this work, the dynamic constraint of the vehicles is taken into account. We seek flyabletrajectories that are only piecewise optimal, i.e. only optimal from one task to the next. Thismakes it possible to represent the problem in the form of a decision tree, the structure of whichenforces the required group coordination and precedence for cooperatively performing the mul-tiple tasks. A tree search algorithm is proposed for solving the investigated UAV cooperativemultiple task assignment problem (CMTAP). Using Euclidean distances for estimating the pathlength encoded in unevaluated branches of the tree enables efficient pruning of the solution tree.Since the algorithm uses a depth first technique, an immediate feasible solution is obtained. Thesolution quality monotonically improves over algorithm run time and converges to the optimalsolution.

The remainder of this manuscript is organized as follows. In the next section, some backgroundon graphs and trees is provided. The UAV CMTAP is then posed as a combinatorial optimizationproblem, and the path planning is discussed. This is followed by a representation of the problemin the form of a decision tree and the derivation of the proposed search algorithm. A Monte Carlosimulation study is then presented and concluding remarks are offered in the last section.

2. GRAPHS AND TREES

Graphs and trees are described in many papers and textbooks including References [7, 8], and willonly briefly be reviewed in this section. Then, some well-known tree search algorithms will bediscussed.

A graph is defined as a set of vertices B and a set of ordered pairings of those vertices E .Thus, the graph is defined as: G = (B, E). Vertices are also termed nodes and each ordered pairof vertices in E is called an edge. Edges can also be thought of as the connection between twovertices. A directed graph is a graph where the edges can only be traversed in a defined direction,i.e. the ordering of the vertices in the edges determines the direction that the edge can be traversed.If the graph is not directed then it is undirected. A graph is said to be connected if for any twovertices a and b, in the graph, there is a path, series of edges, from a to b. A graph contains acycle if it has a path that ends at the same vertex it has started from.

A tree is a directed graph that is connected and does not contain cycles. For combinatorialoptimization problems, decision trees can be constructed that completely enumerate all the possiblesolutions to the problem. A decision tree starts with a single node, trunk, and branches out asmany times as necessary to enumerate the decisions required to solve the problem. The nodes atthe extremities of the tree are the leaves. Except for leaf nodes, each of the nodes in the tree hasone or more child nodes connected to it by edges directed from the parent node to the child node.Each set of edges and nodes connecting the leaf nodes to the trunk node represent a completesolution to the assignment problem. This means that each leaf represents a solution to the problem.The optimal solution to a combinatorial optimization problem can be obtained by completelyenumerating the leaves of the tree, and then finding the leaf with the optimal cost. In practice,finding the optimal solution in this manner is only possible for small-sized problems, becausethe associated computational complexity makes the solution time prohibitively large. It should benoted that in many practical systems obtaining a good solution in an allotted time period is moredesirable than waiting until the optimal solution is reached.

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

138 S. J. RASMUSSEN AND T. SHIMA

For searching trees, the two basic methods are breadth-first and depth-first search (DFS)[9].The breadth-first search explores neighbors of a vertex; that is, outgoing edges of the vertex’spredecessor in the search, before any outgoing edges of the vertex. Since the breadth-first searchexplores all of the parent nodes before exploring the leaf nodes, it can take a long time to find asolution. Because of the desire to reach solutions quickly, the breadth-first search is not consideredin this work. DFS algorithms start at the trunk of the tree and consider outgoing edges of a vertexbefore any neighbors of the vertex; that is, outgoing edges of the vertex’s predecessor in thesearch. The algorithm, easily implemented with recursion, proceeds until a leaf node is reached.The selection of which node to explore at each layer is performed using heuristic arguments. Oncethe DFS reaches a leaf node, it evaluates the next unevaluated child node of the current parentnode. If there is no unevaluated node then the algorithm checks parent nodes until there are nounevaluated nodes in the graph. In this manner, the DFS systematically searches the entire tree.

One variation of the DFS is the best-first search (BFS), where a measure is defined and used tosearch the tree [10]. In this work, the measure used is the lower bound on the cost of assigninga vehicle to perform a task on a target. For each parent node, all the child nodes are evaluatedand the best-cost node is selected. Since at each node all the children nodes need to be evaluated,the BFS is computationally intensive, but tends to arrive early at good solutions. Many othersearch methods such as iterative broadening, limited discrepancy search, and best-leaf first searchhave been developed to take advantage of different types of knowledge on the system in orderto quickly obtain good solutions [11]. The question of which type of search to employ dependson the requirements of the system and the ability to predict which branches will produce bettersolutions.

To obtain the optimal solution, the branch and bound technique can be used [12]. There aremany search strategies based on branch and bound type techniques, see, for example, [13]. Thetechnique that we are using keeps the best solution that has been found thus far as the candidateoptimal solution and uses it as the upper bound for the cost of the assignment. As the cost ofthe nodes are evaluated, they are treated as a loose lower bound by ignoring the remaining tasksencoded in branches of the tree that have not yet been evaluated. If this cost cannot improve onthat of the candidate solution, then this partial assignment is abandoned and the associated part ofthe tree is pruned. The tree can be pruned faster by having a better, higher, lower bound on thecost of the remaining tasks, but obtaining a better bound is associated with a higher computationburden. Resolving this trade-off is of high importance to obtain an efficient algorithm and it isproblem specific.

3. ASSIGNMENT PROBLEM

A generic CMTAP is defined in this section. First, the task requirements are discussed and thenthe path planning problem is presented. Next, different performance measures are reviewed andfinally the assignment is posed as a combinatorial optimization problem.

3.1. Assignment requirements

Let

T ={1, 2, . . . , Nt } (1)

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 139

be the set of ground stationary targets designated to the group, possibly by a human operator, and

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

be the set of UAVs performing tasks on these targets. The number of tasks to be performed oneach target is denoted by Nm . In this assignment problem, the UAVs are required to perform a setof three tasks on each target

M ={C, A, V } (3)

where C , A, and V denote classify, attack, and verify, respectively. Note that, contrary to [3], weare dealing with UAVs and not munitions and thus the vehicles are not destroyed after performingan attack (for example, by releasing a weapon).

Each of these three tasks has requirements governing its execution. Target classification isrequired to ensure that the subject object is the intended target and not a decoy or some othernon-target. To complete a classification task, a vehicle must follow a trajectory that places itssensor footprint on the target at a selected heading angle with respect to the target. After a targethas been successfully classified, one or more UAVs attack it with restrictions on their trajectory.Then, the UAV team must verify that the target was killed using their onboard sensors with givenfootprints. After each UAV fulfills its group tasks (if any) it then resumes a default task, such assearching for new targets.

There is a precedence requirement for the tasks on each target, i.e. the tasks must be accomplishedin order. A target must be first classified, afterwards attacked, and only then verified. In order toutilize the UAVs in an efficient manner coordination is required, i.e. each task must be accomplishedonce. For example, UAVs are not allowed to attack a target twice, unless the target is verifiedalive after an attack or there is a predefined need for multiple attacks. In assigning tasks for theCMTAP, we assume that targets have already been detected and designated to the UAV group; andthat each and every task is expected to be accomplished successfully, i.e. with a probability of 1.If a certain task is not accomplished then the entire assignment algorithm has to be re-run.

3.2. Path planning

For obtaining a real-time solution of the cooperative task assignment problem, it is usually assumedthat the UAVs fly at a constant speed and altitude. This speed can be, for example, the optimalone for energy consumption or the fastest one. We assume that altitude de-confliction can be usedto avoid collision between the UAVs. Thus, in contrast to planning problems for multiple groundrobots, the trajectory of each UAV can be obtained independently. This reduces considerably thecoupling between the trajectories of the UAVs in the group.

To be implementable, the assigned paths must be flyable by the fixed-wing UAVs, having aminimum turning radius. If the path assigned to a UAV is non-flyable, the timing and spatialcoordination of the cooperative assignments may be invalidated. The scale of the scenario isimportant in determining the impact of the flyable path constraint. For example, if the turn radiusof the vehicle is very small when compared to the distance between the targets, then this constraintmay not have a significant impact on the mission.

Based on the state of the UAV a minimum turning radius can be calculated, thus capturing theUAV’s dynamics constraints in the form of a kinematic constraint. Based on this minimum turning

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

140 S. J. RASMUSSEN AND T. SHIMA

radius, we use the Dubin’s car model [14] for representing the planar kinematics of the vehicles:

x = v cos � (4a)

y = v sin � (4b)

� = �maxu (4c)

v = 0 (4d)

where x and y are the UAV horizontal coordinates in a Cartesian inertial reference frame; � is theazimuth flight angle; v is the speed; and �max is the maximum turning rate of the vehicle. It wasshown [14] that the optimal paths for vehicles following the kinematics of Equations (4) consistof straight lines and arcs with radius Rmin = v/�max. More specifically, these optimal paths arefrom two different families: (1) turn-straight-turn and (2) turn-turn-turn. Thus, the control of eachvehicle in the team is restricted to the set

u ∈ {−1, 0, 1} (5)

The cost associated with performing a single assignment by each UAV is calculated using the pathoptimization function of the MultiUAV2 simulation [15]. In order to obtain a flyable trajectory, theDubin path calculation is performed using Rmin based on the above equations of motion. A singleDubin’s path is constructed for each required task for given heading constraints at the start and endpoints. The heading at the end of each task segment is calculated based on the task requirements.These calculations are based on an heading optimization using the methods described in [16]. Theend conditions of one task path segment are used as the initial conditions for the next.

The entire planned path of the UAV is constructed from these task segments. This procedureresults in a smooth path constructed from optimal task segments. Note that an optimal path, for allthe assigned tasks, could be obtained, but would require intensive computational effort. Moreover,computing the optimal path for an entire assignment would not facilitate forming the decisionproblem as a tree and thus will not permit decoupling the problem of decision from that of pathoptimization.

3.3. Performance index

Different performance criteria can be chosen for the UAVCMTAP. Two such criterions are presentednext.

One performance criterion that can be used is the cumulative distance traveled by the vehiclesto perform all the required tasks:

J1 =Nu∑i=1

Di>0 (6)

where Di is the distance traveled by UAV i ∈U from the beginning of the mission until finishingits part in the group task plan. The group objective is to minimize J1 subject to the assignmentrequirements of Section 3.1. By minimizing this cost function, composed of the cumulative dis-tances traveled by all the UAVs participating in the group assignment, the use of the overall groupflight time resource (assuming constant fuel consumption) is optimized. After each UAV fulfills

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 141

its group tasks, if any, it can then resume a default task such as searching for new targets. Thiscost function is appropriate mainly for problems involving low value stationary targets.

Another possible performance criterion is makespan, i.e. the time it takes the team to accomplishthe required tasks on all targets. Assuming constant equal speeds for all agents, this performancecriterion is

J2 = maxi∈U Di>0 (7)

Thus, the group objective is to minimize the longest distance traversed by one (or more) of itsmembers subject to the assignment requirements of Section 3.1. This cost function can be used ina scenario where it is critical to service targets as quickly as possible. Such scenarios are that ofhigh value movable targets, e.g. hunting mobile ballistic missile launchers.

3.4. Combinatorial optimization problem

The problem is to minimize the cost function J1 of Equation (6) or J2 of Equation (7), by optimizingthe Nc assignments of vehicles to targets where

Nc = NmNt (8)

Let

S ={1, 2, . . . , Nc} (9)

be the set of stages, in which the assignment is made. Let

xl,i, j ∈ {0, 1} (10)

be a decision variable, that is, 1 if at stage l ∈ S vehicle i ∈U performs a task on target j ∈ T andis 0 otherwise; and

Xl = {x1,i, j , x2,i, j , . . . , xl,i, j } (11)

be the set of assignments up to, and including, stage l.Let cXl−1

l,i, j be the length of Dubin’s trajectory traveled by vehicle i ∈U to perform a task ontarget j ∈ T at a stage l ∈ S, given the prior assignment history Xl−1. Note that this assignmenthistory is used to obtain the initial condition for calculating the optimal Dubin’s trajectory to betraveled, satisfying Equations (4).

Let bi be the resource availability of vehicle i ∈U , in which the investigated case is defined asthe total distance each vehicle can travel.

The mathematical formulation of the CMTAP with the two different cost functions is givennext, where Equation (12) corresponds to the cost function of Equation (6), and Equation (13) tothat of Equation (7). Thus, the problem is

min

[J1 =

Nc∑l=1

Nu∑i=1

Nt∑j=1

cXl−1l,i, j xl,i, j

](12)

or

min

[J2 = max

Nc∑l=1

Nt∑j=1

cXl−1l,i, j xl,i, j , i ∈U

](13)

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

142 S. J. RASMUSSEN AND T. SHIMA

s.t.

Nu∑i=1

Nt∑j=1

xl,i, j = 1, l ∈ S (14)

Nc∑l=1

Nu∑i=1

xl,i, j = Nm, j ∈ T (15)

Nc∑l=1

Nt∑j=1

cXl−1l,i, j xl,i, j�bi , i ∈U (16)

and Equations (4), (5), (8)–(11). Note that we denote the cost of the optimal assignment as J opti ,

where J opti = min Ji ; i = 1, 2.Equation (14) ensures that at each stage exactly one task on a target j ∈ T is assigned to exactly

one vehicle i ∈U ; Equation (15) ensures that on each target j ∈ T exactly Nm tasks are performed;and Equation (16) ensures that the total resource requirement of the tasks from each vehicle i ∈Udoes not exceed its capacity.

4. TREE REPRESENTATION

In this section, first a tree representation of the CMTAP will be presented. Then, the problem’scomputational complexity will be analyzed.

4.1. Tree structure

In Figure 1, a tree representation of possible assignment permutations, without taking into accountthe precedence requirement, for a scenario between two UAVs and one target is illustrated. Each ofthe nodes in the tree represents the assignment of a vehicle to a task that needs to be accomplished.The edges link nodes that can be aggregated into a group assignment. Each node defines a singletask by a single UAV on a single target; where Ci, j , Ai, j and Vi, j denote that vehicle i ∈U isto perform a classification, attack, or verify task, respectively, on target j ∈ T . In this figure, itis apparent that task coordination is enforced, i.e. no assignment is performed by more than onevehicle. When the task precedence requirement is applied to the tree, all the unfeasible assignments,indicated by the faded entries, are pruned. Figure 2 shows a partial plot of feasible branches ofthe tree for the scenario of three UAVs servicing two targets. Note that such a tree is very widecompared to its depth.

During construction of the tree, parent nodes are evaluated before child nodes. This means thatthe state of the assignments, i.e. task times and vehicle states, evolve as the tree is constructed.The cost associated with each node is calculated by using the path optimization function of theMultiUAV2 simulation [15]. This function calculates the relevant cXl−1

l,i, j to be used in Equation (12)or (13). For the calculation, the path is optimized as discussed in Section 3.2. Thus, the need forflyable trajectories is enforced and the time that the task is to be performed is calculated.

If the vehicle is calculated to arrive at a target before the prerequisite task time, i.e. beforethe time that the last task is to be performed, a path elongation algorithm is used, thus satisfyingthe timing constraints. For the path elongation, we use the algorithm described in [16] where

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 143

Figure 1. All possible assignment permutations for a Nu = 2, Nt = 1, Nm = 3 scenario.

elongated paths are generated off the original, shortest, path. Using the shortest path allows thecritical trajectory information to be known, such as initial and final turn directions.

The computation of cXl−1l,i, j for l�2 is dependent on the tasks performed by vehicle i prior to step

l, since those tasks effect its path and the current prerequisite task times. Thus, cXl−1l,i, j cannot be

computed a priori and is different for every assignment. Note that the trajectory path planning isperformed independently for each stage l ∈ S. Thus, at each stage, the path optimization is decoupledfrom the assignment problem. This can result with a suboptimal solution, i.e. a piecewise optimalpath. However, it greatly simplifies the computational complexity of the problem.

Once the tree is constructed, the number of leaves (nodes at the end of the branches of thetree) represents the number of feasible assignments. That is, constructing the tree in this mannercompletely enumerates all possible feasible solutions to the CMTAP. Since the assignment infor-mation is encoded in the nodes, beginning at one of the leaf nodes and traversing the tree back tothe starting node defines the set of task assignments and trajectories necessary to perform all therequired tasks on the targets.

4.2. Computational complexity

The computational complexity of the problem addressed in this paper is governed by the calculationsof Dubin’s trajectories using the path optimization function of the MultiUAV2 simulation [15]. Asexplained in the previous subsection, this function calculates the relevant cXl−1

l,i, j of each node to be

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

144 S. J. RASMUSSEN AND T. SHIMA

Figure 2. Sample of feasible assignments for a Nu = 3, Nt = 2, Nm = 3 scenario.

used in Equation (12) or (13). Thus, the amount of nodes that needs be evaluated, to first obtaina feasible solution and then the optimal one, is of essence.

4.2.1. Exhaustive enumeration. The depth of the tree, i.e. the number of nodes on a branch fromthe root node to the leaf nodes is equal to the number of assignments Nc. Let

L ={1, 2, . . . , Nc} (17)

be the set of layers of the tree.Each node in the tree can be connected by edges up to Nd nodes in the next layer, where

Nd = Nt Nu (18)

Thus, the number of nodes in each layer of the tree i ∈ L is upper bounded by Nid .

For i = 1, 2, 3, the bound in (19) is equal to the actual number of nodes in these layers, as alltargets still remain in the assignment pool.

In the last layer, only a single target is left. Similarly, in layer i ∈ L \ {1, 2, . . . , Nc − Nt + 1}at most Nc − i + 1 targets are left. Thus, a tighter bound for the number of nodes in each of thelast Nt − 1 layers is

Nn(i)= NiuN

Nc−Nt+1t (Nt − 1)!/(Nc − i)!, i ∈ L \ {1, 2, . . . , Nc − Nt + 1} (19)

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 145

24

68

10

34

56

78

9

1015

100

105

1010

NuNtNm

1e0

1e5

1e10

1e12

Figure 3. Number of feasible assignments; Nm = 3.

Using these relations, the total number of nodes that need to be evaluated in exhaustivelysearching the tree is upper bounded by

Ntotal =Nc−Nt+1∑

i=1Nid +

Nc∑i=Nc−Nt+2

Nn(i) (20)

4.2.2. Best-first search. If at each layer one node is selected and its children nodes expanded (i.e.the cost is evaluated), then the upper bound on the number of evaluated nodes is

NeU = NuNt [0.5(1 − Nt ) + Nt Nm] (21)

while the lower bound is

NeL = NuNmNt (Nt + 1)/2 (22)

NeU and NeL represent the upper and lower bounds on the number of nodes that need to beevaluated to perform a best-first search on the tree.

4.2.3. Feasible assignments. The number of leaf nodes, i.e. assignment permutations, in the treesuch as that of Figure 1, is given by

Np = NuNc(Nc)! (23)

This quantity includes also unfeasible assignments. If the precedence requirement is enforced, thenthe number of feasible assignments reduces to

N f = Nc!Nm !Nt

NuNc (24)

In the example plotted in Figure 1 Np = 48 while N f = 8. The dependence of N f on the numberof vehicles and targets for the UAV CMTAP is plotted in Figure 3.

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

146 S. J. RASMUSSEN AND T. SHIMA

Figure 4. Tree search algorithm flow chart.

5. SEARCH ALGORITHM

Our search algorithm is initiated by a BFS algorithm that provides an immediate feasible assign-ment. The algorithm starts at the trunk of the tree and the estimated cost of each child is calculatedby using the lower-bound Euclidean distance between the assigned vehicle and its designated

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 147

target. The child node with the smallest estimate is selected and the cost of a flyable Dubin’s pathto perform the assignment is evaluated using the, computationally intensive, path optimizationfunction of the MultiUAV2 simulation [15], discussed in Section 3.2. The process is repeated ineach layer of the tree until a leaf node is reached. The feasible assignment encoded in the branchspecified by this leaf serves as a candidate optimal assignment for our search algorithm.

The key to an efficient tree search algorithm is its ability to quickly prune parts of the tree. Thecost of a candidate optimal solution, obtained initially using the BFS algorithm discussed above,provides an upper bound on the cost of the cooperative assignment. The flow chart depicting theoptimization algorithm for the CMTAP is shown in Figure 4. We begin the search at the leaf nodeobtained from the BFS algorithm. Using Euclidean distances, we quickly obtain a lower boundon the cost of the same target being serviced by a different UAV in the group. If the cost islarger than that of the candidate optimal assignment, then this node is pruned. If not, then the,computationally intensive, path optimization subroutine is used to obtain the actual cost of the nodewith the smallest Euclidean distance, and the node is considered evaluated. We compare the costto that of the candidate optimal assignment; and if it is lower, then it becomes the new candidateoptimal solution. We apply these upper and lower bounding procedures iteratively traversing thetree upwards and downwards. Note that when nodes that are not at the extremities of the tree areevaluated their cost is treated as a loose lower bound by ignoring the remaining tasks encodedin child nodes that have not yet been evaluated. The above procedure enables efficient pruningof the solution tree and obtaining a monotonically improving assignment solution. The search isterminated when all nodes have either been evaluated or pruned.

6. RESULTS

The scenario investigated is between three UAVs performing three tasks on each of the four targets.To test the performance of the algorithm, a set of 50 different engagements was constructed. Forevery engagement, the position and heading of each vehicle and the position of each target wereselected using random draws from a uniform distribution. Using this set of engagements, thealgorithms were evaluated for three turn radii of 0, 500, and 1500 (ft). In order to comparebetween different runs in the set, the obtained results were normalized by the cost of the optimalassignment (J opti ; i = 1, 2) that the algorithm eventually converges to. The computer used to runthe algorithm was based on multiple dual 3.0GHz Intel Xeon processors.

Investigating the effect of the vehicles’ turn radius on the method, the mean normalized valueof the assignments, E(Jopt/J ), is plotted versus the solution time in Figures 5 and 6, for J1 andJ2, respectively. In all the cases, the initial solutions are found as quickly as possible, after theminimum number of nodes have been processed for the BFS. Note that for the investigated scenarioNeL = 90 and NeU = 126. These figures show that, for the shorter turn radius cases, the normalizedvalues start closer to the optimal and converge faster. This result is expected since the Euclidianapproximation is better as the turn radius is reduced, allowing faster pruning of the search space.

Figures 7–9 show sample trajectories of the optimal assignments for a single scenario usingthree different turn radii and the J1 cost function; similarly, Figures 10–12 are obtained for the J2cost function. In these figures, the vehicles’ initial positions are marked with disks and the targetpositions are marked with squares. The lines represent the trajectories assigned to each vehicle. Inthese cases, the initial location of the targets and the location and heading of the members of theUAV team are identical. The path of each UAV is plotted from its initial location until completion

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

148 S. J. RASMUSSEN AND T. SHIMA

10010–2 102 1040

0.2

0.4

0.6

0.8

1

Time (sec)

Rmin=0 [ft]

Rmin=500 [ft]

Rmin=1500 [ft]

E(J

1

/J1)

opt

Figure 5. Mean solution times for the 3 × 4 × 3 scenario, J1 cost function.

10010–2 102 1040

0.2

0.4

0.6

0.8

1

Time (sec)

Rmin=0 [ft]

Rmin=500 [ft]

Rmin=1500 [ft]

E(J

2

/J2)

opt

Figure 6. Mean solution times for the 3 × 4 × 3 scenario, J2 cost function.

of its part of the task assignment; thus, when a UAV does not participate in executing the grouptask assignment, as is the case for vehicle 2 in Figures 8 and 9, only its initial location is shown.Note that in the scenario plotted in Figures 7 and 10, where the minimal turn radius constraintis not active (i.e. Rmin = 0), possible, for example, for hovering aircraft, the vehicles retrace theirattack trajectories to perform the verification tasks.

In Figure 7, plotted for the case with no turning limitation, all vehicles participate in theassignment. Vehicle 1 is assigned to classify, attack, and verify targets 3 and 2; vehicle 2 isassigned to classify, attack, and verify target 4; and vehicle 3 is assigned to classify, attack, andverify target 1. Figure 8 is plotted for a minimum turn radius of 500 (ft). Here only vehicles 1 and

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 149

0 5000 100000

5000

10000

1

23

1

2

3

4

X [ft]

Y [f

t]

Figure 7. J1, Rmin = 0.

0 5000 100000

5000

10000

12

3

1

2

3

4

X [ft]

Y [f

t]

Figure 8. J1, Rmin = 500.

3 participate. Vehicle 1 is assigned to classify and attack targets 4 and 1, and then verify target1; while vehicle 3 is assigned to classify and attack targets 2 and 3, then verify targets 4 and 3,and finally, verify target 2. When the minimum turn radius is raised to 1500 (ft) then again onlyvehicles 1 and 3 participate, as can be seen in Figure 9. Vehicle 1 is assigned to classify and attacktarget 2; while vehicle 3 carries out the rest of the group plan, classifying and attacking targets 3,4, 1, and then verifying targets 2, 3, 4, and 1.

From these figures, it can be seen that different assignments and trajectories are obtained forthe different turn radii reflecting on the level of apparent cooperation. With larger turn radii, lessvehicles are assigned to participate in the mission, e.g. Figure 9 with Rmin = 1500 (ft) has vehicle3 performing most of the tasks. When the turn radius is reduced from 1500 to 500 (Figure 8),the tasks are being more evenly distributed between vehicles 1 and 3. With no turning limitation

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

150 S. J. RASMUSSEN AND T. SHIMA

0 5000 100000

5000

10000

1

23

1

2

3

4

X [ft]

Y [f

t]

Figure 9. J1, Rmin = 1500.

0 5000 100000

5000

10000

X [ft]

Y [f

t]

1

23

1

2

3

4

Figure 10. J2, Rmin = 0.

(Figure 7), the tasks are distributed among all three vehicles. This change in the level of apparentcooperation is due to the extra distance required for a vehicle to travel to perform tasks when turnconstraints are imposed.

For the selected example, when the J2 cost function is used, all the vehicles participate in theassignment for all of the turn radii. This can be seen from Figures 10–12 plotted for turn radii of0, 500, and 1500 (ft), respectively. In Figure 10 vehicle 1 is assigned to classify and attack target3 and then classify, attack, and verify target 2; vehicle 2 is assigned to verify target 3 and thenclassify, attack, and verify target 4; at the same time, vehicle 3 will classify, attack, and verifytarget 1. The 500 (ft) turn radius case is shown in Figure 11. In this case, vehicle 1 will performall of the required tasks on target 1; vehicle 2 will classify and attack target 4, and then verifytargets 3 and 2; meanwhile, vehicle 3 will classify and attack targets 2 and 3 and then verifies

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 151

0 5000 100000

5000

10000

X [ft]

Y [f

t]

1

23

1

2

3

4

Figure 11. J2, Rmin = 500.

0 5000 100000

5000

10000

X [ft]

Y [f

t]

1

23

1

2

3

4

Figure 12. J2, Rmin = 1500.

target 4. For the 1500 (ft) case, Figure 12, vehicle 1 classifies and attacks target 2 and then verifiestargets 3 and 4; vehicle 2 will classify and attack targets 1 and 4; finally, vehicle 3 will classifyand attack target 3 and then verifies targets 2 and 1.

As can been seen from these examples using the cost function J2, makes it likely that, comparedwith the use of J1, more vehicles will be used to complete all of the assigned tasks. This phenomenonis typical over the Monte Carlo simulations and is the result of the need to finish the entireassignment as quickly as possible regardless of the resources used (vehicles’ cumulative fuel/flighttime). This has the effect of increasing the amount of apparent cooperation between the vehicleswhen using the J2 compared with J1 cost function.

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

152 S. J. RASMUSSEN AND T. SHIMA

7. CONCLUSIONS

The representation of the cooperating UAVs assignment problem as a tree that need be searchedenables enforcement of the required group coordination and precedence on cooperatively perform-ing multiple tasks on multiple targets. Due to the prohibitive computational complexity of theproblem, exhaustive enumeration of all the assignments encoded in the tree is not feasible. Theproposed tree search algorithm has desirable qualities such as providing fast an initial feasiblesolution that monotonically improves and converges to the optimal solution. The algorithm can beapplied on line to different sized problems. For small-sized problems, it will provide the optimalsolution whereas for large-sized problems an immediate feasible solution that improves over runtime is obtained. The algorithm can also be used off line to obtain the optimal solution needed toevaluate the performance of other sub-optimal search methods.

During the search of the tree, candidate optimal solutions serve as an upper bound for the costof the assignment. Using Euclidean distances for estimating the path length encoded in branchesof the tree that have not yet been evaluated, by the computationally intensive Dubin’s optimizationsubroutine, provides a lower bound for their cost. Applying these upper and lower boundingprocedures iteratively on active subsets within the feasible set, enables efficient pruning of thesolution tree.

ACKNOWLEDGEMENTS

The first author is an on-site contractor with General Dynamics. The work of the second author waspartially supported by a National Research Council Research Associateship Award at the Control ScienceCenter of Excellence, AFRL, Wright-Patterson AFB and partially supported by a Horev Fellowship throughthe Taub Foundation, and the Bernard M. Gordon Center for Systems Engineering, at the Technion.

REFERENCES

1. Pardesi MS. Unmanned aerial vehicles/unmanned combat aerial vehicles: likely missions and challenges for thepolicy-relevant future. Air and Space Power Journal 2005; XIX(3):45–54.

2. Richards A, Bellingham J, Tillerson M, How JP. Coordination and control of multiple UAVs. Proceedings of theAIAA Guidance, Navigation, and Control Conference, Monterey, CA, 2002.

3. Schumacher CJ, Chandler PR, Pachter M, Pachter L. Constrained optimization for UAV task assignment.Proceedings of the AIAA Guidance, Navigation, and Control Conference, Providence, RI, 2004.

4. Schumacher CJ, Chandler PR, Rasmussen SJ. Task allocation for wide area search munitions. Proceedings ofthe American Control Conference, Anchorage, Alaska, 2002.

5. Chandler PR, Pachter M, Rasmussen S, Schumacher C. Multiple task assignment for a UAV team. Proceedingsof the AIAA Guidance, Navigation, and Control Conference, Monterey, CA, 2002.

6. Schumacher CJ, Chandler PR, Rasmussen SJ. Task Allocation for wide area search munitions via iterativenetwork flow optimization. Proceedings of the AIAA Guidance, Navigation, and Control Conference, Monterey,CA, 2002.

7. Kaufmann A. Graphs, Dynamic Programming, and Finite Games (1st edn). Mathematics in Science andEngineering, vol. 36. Academic Press: New York, 1967.

8. Hartsfield N, Ringel G. Pearls in Graph Theory: A Comprehensive Introduction (1st edn). Academic Press:Boston, MA, 1994.

9. Siek J, Lee L-Q, Lumsdaine A. The Boost Graph Library: User Guide and Reference Manual (1st edn).Addison-Wesley: Boston, MA, 2002.

10. Pearl J. Heuristics: Intelligent Search Strategies for Computer Problem Solving. Addison-Wesley: Reading, MA,1984.

11. Ruml W. Adaptive tree search. Ph.D. Thesis, Harvard University, May 2002.

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc

TREE SEARCH 153

12. Papadimitriou CH, Steiglitz K. Combinatorial Optimization: Algorithms and Complexity (2nd edn). Dover: NewYork, 1998.

13. Linderoth JT, Savelsbergh M. A computational study of search strategies for mixed integer programming. ReportLEC-97-12, Georgia Institute of Technology, 1999.

14. Dubins L. On curves of minimal length with a constraint on average curvature, and with prescribed initial andterminal position. American Journal of Mathematics 1957; 79:497–516.

15. Rasmussen SJ, Mitchell JW, Schulz C, Schumacher CJ, Chandler PR. A multiple UAV simulation for researchers.Proceedings of the AIAA Modeling and Simulation Technologies Conference, Austin, TX, 2003.

16. Schumacher CJ, Chandler PR, Rasmussen SJ, Walker D. Path Elongation for UAV task assignment. Proceedingsof the AIAA Guidance, Navigation, and Control Conference, Austin, TX, 2003.

Copyright q 2007 John Wiley & Sons, Ltd. Int. J. Robust Nonlinear Control 2008; 18:135–153DOI: 10.1002/rnc


Recommended