Next Article in Journal
Dynamic Cascade Spiking Neural Network Supervisory Controller for a Nonplanar Twelve-Rotor UAV
Next Article in Special Issue
A Lossless Scalar Calibration Algorithm Used for Tri-Axial Magnetometer Cross Array and Its Effectiveness Validation
Previous Article in Journal
Weather-Adaptive Regenerative Braking Strategy Based on Driving Style Recognition for Intelligent Electric Vehicles
Previous Article in Special Issue
Empowering People with Disabilities in Smart Homes Using Predictive Informing
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Autonomous Mission Planning for Fixed-Wing Unmanned Aerial Vehicles in Multiscenario Reconnaissance

1
School of Aeronautics and Astronautics, University of Electronic Science and Technology of China, Chengdu 611731, China
2
AVIC (Chengdu) Unmanned Aerial Vehicle Systems Co., Ltd., Chengdu 611743, China
3
System of Systems and Artificial Intelligence Laboratory, Chendu 610041, China
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(4), 1176; https://doi.org/10.3390/s25041176
Submission received: 28 November 2024 / Revised: 20 January 2025 / Accepted: 10 February 2025 / Published: 14 February 2025

Abstract

:
Before a fixed-wing UAV executes target tracking missions, it is essential to identify targets through reconnaissance mission areas using onboard payloads. This paper presents an autonomous mission planning method designed for such reconnaissance operations, enabling effective target identification prior to tracking. Existing planning methods primarily focus on flight performance, energy consumption, and obstacle avoidance, with less attention to integrating payload. Our proposed method emphasizes the combination of two key functions: flight path planning and payload mission planning. In terms of path planning, we introduce a method based on the Hierarchical Traveling Salesman Problem (HTSP), which utilizes the nearest neighbor algorithm to find the optimal visit sequence and entry points for area targets. When dealing with area targets containing no-fly zones, HTSP quickly calculates a set of waypoints required for coverage path planning (CPP) based on the Generalized Traveling Salesman Problem (GTSP), ensuring thorough and effective reconnaissance coverage. In terms of payload mission planning, our proposed method fully considers payload characteristics such as scan resolution, imaging width, and operating modes to generate predefined mission instruction sets. By meticulously analyzing payload constraints, we further optimized the path planning results, ensuring that each instruction meets the payload performance requirements. Finally, simulations validated the effectiveness and superiority of the proposed autonomous mission planning method in reconnaissance tasks.

1. Introduction

In recent years, fixed-wing UAVs have played an increasingly important role in various reconnaissance mission scenarios. Their unique flight performance and long endurance capabilities have demonstrated significant application potential in both military reconnaissance and civilian monitoring fields [1,2,3]. One crucial application is target tracking [4,5,6]. Before a fixed-wing UAV executes target tracking missions, it is crucial to first identify targets within reconnaissance mission areas using onboard payloads. This paper presents an autonomous mission planning method designed for these reconnaissance operations, enabling effective target identification prior to initiating tracking tasks. We believe that UAVs completing reconnaissance missions must address two main aspects: path planning and payload planning. However, traditional planning methods are often limited to single-objective optimization, such as focusing on flight performance, obstacle avoidance, and energy consumption [7,8,9], while neglecting the deep integration of payload characteristics.
Currently, UAV path planning works are primarily focused on applications with single scenarios, lacking consideration of different scenarios. Cui [10] formulated the problem of multiple single-point reconnaissance targets as a Dynamic Constrained Traveling Salesman Problem with Neighborhoods (DCTSPN) and proposed a hierarchical algorithm based on deep reinforcement learning to solve it. Although the effectiveness of this algorithm was validated, it is well known that learning-based methods are not interpretable. Zhang et al. [11] proposed a bi-level hybridization-based metaheuristic algorithm for fixed-wing UAVs used in forest fire monitoring. While this algorithm can reduce data collection cycles and energy consumption in most cases, it is limited to single-point targets, restricting its applicability to other scenarios. At the same time, the coverage path planning (CPP) problem has garnered increasing attention [12,13,14,15], especially in missions requiring UAVs to scan entire areas. The CPP problem involves planning a path that covers all Regions of Interest (ROI) while avoiding obstacles or no-fly zones [16,17,18]. Different CPP methods have their own advantages and limitations. Selecting an appropriate CPP method requires the consideration of specific application requirements and environments [19]. Barrientos et al. [20] proposed a Breadth First Search (BFS)-based coverage planner, which can be applied to grid-based workspaces to generate paths with minimal turning maneuvers. However, search-based methods have high computational complexity, particularly in large-scale environments where they require substantial computational resources, making them unsuitable for long-endurance fixed-wing UAVs. In [21], a random walk-based CPP algorithm for robots was introduced. This method is simple and has low memory requirements, making it easy to deploy. However, random walk paths are only suitable for smaller environments and struggle to cover ROI with obstacles. Additionally, the robot may traverse the same path multiple times, leading to overall inefficiency in the coverage path. Bähnemann et al. [22] proposed a decomposition-based CPP algorithm for quadrotor, which extends the Boustrophedon Cell Decompositon (BCD) [23,24,25] by optimizing different sweep combinations to find the optimal sweep path and accounting for obstacles between the decomposed cells. This method is computationally efficient, easy to implement, and effectively handles complex areas.
Although the above works have achieved significant results in reconnaissance path planning for single-point or ROI targets, few works have been able to combine these two typical scenarios. Additionally, these studies have not adequately considered the role of payloads in the planning process. We need to clearly recognize that path planning without effective payload used for reconnaissance integration cannot ensure the successful execution of flight missions [26,27,28,29]. We introduce a reconnaissance fixed-wing UAV, typically operating at altitudes above 5000m, equipped with Synthetic Aperture Radar (SAR) systems for aerial reconnaissance [30,31]. SAR systems have two operating modes: beam forming [32] and strip modes [33]. One of the most challenging aspects of mission planning is adjusting the UAV’s path based on the payload. This complexity arises from the need to combine the payload’s system response time, imaging width, and others with the existing flight plan. Such integration is crucial for meeting mission requirements.
Therefore, this paper takes this as a motivation to explore how to achieve autonomous mission planning for fixed-wing UAVs in multiscenario reconnaissance. The innovations of this paper include the following: Firstly, in Section 2, we designed a path planning algorithm featuring the HTSP. This algorithm initially solves the TSP problem using the nearest neighbor algorithm to determine the reconnaissance sequence for different mission targets. Additionally, by incorporating the BCD technique, it addresses the coverage problem for area targets. We transformed the GTSP problem into a graph structure, ensuring the accuracy of the planning results. Fixed-wing UAVs need to switch flexibly between different mission scenarios. In Section 3, the proposed payload planning module considers the characteristics, workflow, and instruction parameters of the payload. It adjusts the pre-planned waypoint set according to the payload’s operating mode. Furthermore, to ensure the safety of UAV transitions between distinct mission scenarios, a visibility graph obstacle avoidance algorithm was integrated to refine the waypoint sets. Finally, in Section 4, we developed a user-friendly UI interface that supports visualization and adjustment, and validated the effectiveness of the autonomous mission planning module in multiscenario situtations.

2. HTSP Path Planning

In multiscenario situations, UAVs must visit multiple point targets, which are specific locations, and area targets, which are ROI with defined boundaries. This problem can be modeled as an HTSP. The main challenge of HTSP is to determine the sequence of visiting each target to ensure the shortest flight path, as well as to plan the coverage flight path within each area target.
To address the HTSP problem, we adopt a two-stage strategy:
  • Sequence Planning: This stage determines the order of visiting different scenarios. By optimizing the sequence, the UAV can minimize the overall flight range.
  • Coverage Path Planning: The lower level addresses the coverage of area targets using BCD. This ensures that the UAV efficiently covers each area while adhering to constraints such as no-fly zones.

2.1. Sequence Planning

The inputs for the autonomous mission planning module include the entry point S , the exit point E , the set of no-fly zones or obstacle Obs , the set of area target F , and the set of point targets M .
S = { x S , y S , h S } E = { x E , y E , h E } Obs = { obs 1 , obs 2 , , obs i } obs i = { o p i 1 , o p i 2 , , o p i n } o p i n = { x i n , y i n , h i n } F = { f 1 , f 2 , , f j } f j = { { f v j 1 , f v j 2 , , f v j n } , m o d e , i w } f v j n = { x j n , y j n , h j n } M = { m 1 , m 2 , , m k } m k = { x k , y k , h k , m o d e , i w }
In (1), x, y, and h represent the two-dimensional coordinates and altitude, respectively. obs i denotes the no-fly zones constructed as polygons, with their vertices represented by o p i n . f j represents the area targets, also constructed as polygons, with their vertices represented by f v j n . m k refers to the point targets. m o d e and i w are integer variables indicating the payload operating mode and imaging width, respectively.
Sequence planning uses the nearest neighbor algorithm not only to determine the traversal order but also to further output the entry points for the coverage paths of polygonal area targets. Identifying the entry points for area targets helps minimize the overall path length. When covering polygons, choosing entry points judiciously can prevent redundant paths, thereby reducing the total flight range. The point set V is constructed as follows:
V = n = 1 m f p j n k = 1 l M k { S , E }
where m represents the number of area targets and l represents the number of point targets. To compute the Euclidean distance between any two points in the set V, we obtain the distance matrix D:
D i j = ( x i x j ) 2 + ( y i y j ) 2
where ( x i , y i ) and ( x j , y j ) are the coordinates of points V i and V j , respectively. Using the nearest neighbor algorithm, we solve for the path from the entry point S to the exit point E that passes through all points, denoted as T s e q . We initialize the current node as c u r r e n t = v 0 and the starting point as v 0 = S . We initialize a boolean array v i s i t e d to mark the visit status of all nodes, where all nodes are initially unvisited: v i s i t e d = { false , false , , false } . We mark the starting node v 1 as visited: v i s i t e d [ 0 ] = true ). We initialize the sequence T seq and add the starting node to the sequence: T seq = [ v 1 ] .
We loop from the starting node to the second-to-last node, executing the following iterative steps: For each node i from 1 to n 2 , we select the node n e x t closest to node c u r r e n t among all unvisited nodes, and thus we have:
n e x t = arg min j visited D c u r r e n t , j
We add n e x t to the sequence:
T s e q = T s e q { n e x t }
We update the current node.
c u r r e n t = n e x t
We mark node n e x t as visited.
v i s i t e d [ next ] = true
Finally, we add the exit point v n 1 = E to the sequence.
T s e q = T s e q { v n 1 }
From Equations (4)–(8), we use the nearest neighbor algorithm to obtain the shortest sequence of point set T s e q from S to E .
Finally, we determine the entry point of each polygon based on T s e q . We initialize the entry point array for each polygon e n t r y _ p o i n t s :
e n t r y _ p o i n t s = { ( 0 , 0 ) } i = 1 m
We initialize the polygon visit array p o l y _ v i s i t e d :
p o l y _ v i s i t e d = { false } i = 1 m
We iterate over each element V i in the sequence T s e q . If V i belongs to the i-th polygon and this polygon has not yet been visited, then we set V i to:
e n t r y _ p o i n t s [ i ] = V i
We mark the i-th polygon as visited.
p o l y g o n _ v i s i t e d [ i ] = t r u e
Through the formalization shown above, we can comprehensively describe the nearest neighbor algorithm for solving the approximate TSP problem, ensuring that the shortest sequence of target visits and entry points is determined from the start S to the end E .

2.2. Coverage Path Planning with Area Target

For UAVs equipped with SAR systems, continuous scanning is performed along the coverage path during a single pass over the area target. The data collected are processed by algorithms to generate high-resolution images. However, suboptimal flight paths can significantly degrade image quality. To ensure optimal scanning, the planning of a UAV’s coverage path becomes even more critical.
To address the coverage path planning problem, the module employs the BCD algorithm to divide area targets with no-fly zones into multiple cells. This decomposition ensures that each cell is a simple polygon free of no-fly zones.
BCD is a method used to divide an AOI into smaller, simpler cells that can be covered systematically. The main goal is to ensure the complete coverage of the area while avoiding obstacles, ensuring efficient traversal and minimizing the total path length.
Let us consider an AOI f j represented as a polygon with vertices { f v j 1 , f v j 2 , , f v j n } . The AOI may contain no-fly zones Obs , each represented as a polygonal region. The task is to cover the area f j while avoiding these no-fly zones. The algorithm identifies critical points on the boundaries of f j and Obs , which are points where the sweep line direction changes. This could be the vertices of f j and Obs . A sweep line moves from left to right (or top to bottom), dividing the area into cells whenever it encounters a critical point. The cells are simple polygons, free from any no-fly zones.
Each cell C j k is formed as a result of the sweep line passing through critical points. Mathematically, a cell C j k is represented as:
C j k = f j i = 1 m obs i
where C j k is a simple polygon without holes, and m is the number of obstacles in the AOI.
Within each cell, a systematic back-and-forth (Boustrophedon) motion is used to cover the entire area. This motion can be described mathematically by generating parallel lines inside the cell, ensuring that they cover the cell fully without overlapping.
We choose a direction for the parallel lines. This is often chosen as perpendicular to the longest edge or the edge that aligns best with the general shape of the cell to minimize the number of turns. Let this direction be denoted by a unit vector d .
The coverage path within C j k is generated as a set of parallel lines l k i that are spaced apart by the offset Δ f . These lines are perpendicular to the chosen direction d . Mathematically, l k i can be represented as:
l k i : r = r 0 + i Δ f d , i = 0 , 1 , 2 , , n
where r is the position vector of a point on the line. r 0 is the position vector of the starting point of the first line L 0 , typically taken as the intersection of the first line with the boundary of C j k . These lines are separated by a distance called offset, denoted as Δ f . d is a unit vector perpendicular to d . n is the number of parallel lines required to cover the entire cell.
For each line segment l k i , we identify the start and end points:
P k i = p k i s t a r t , p k i e n d , i = 0 , 1 , 2 , , n
Consequently, we obtain a set of all waypoints for the UAV to cover C j k , which can be represented as:
P j k = { P k 1 , P k 2 , }
To minimize the total path length of the UAV, the coverage paths between adjacent cells are optimized. The objective is to find the optimal sequence for visiting cells, ensuring that each cell is visited exactly once. This problem is typically addressed using graph-based algorithms, and it is modeled as a GTSP.
The GTSP formulation [34,35] for UAV coverage path planning is defined as follows:
Min i = 1 m j = 1 m d i j x i j
where d i j represents the travel distance between cell i and cell j. x i j is a binary decision variable indicating whether the UAV travels directly from cell i to cell j. N is the set of all cells.
The optimization is subject to the following constraints:
Constraints:
  • Binary decision variables:
    x i j { 0 , 1 } i , j
  • We set the start O to the cell where the entry point E obtained in Section 2.1 is located.
    i V x O i = 1
    V is the set of cells except O.
  • We ensure that each cell is entered and left at most once:
    i N x i j 1 j V
    j N x i j 1 i V
  • Subtour elimination constraints (Miller–Tucker–Zemlin formulation):
    u i u j + m · x i j m 1 i , j V , i j
    1 u i m 1 i V
    where u i is an auxiliary variable which keeps the number of visited cells until cell i in the solution. These constraints ensure that the solution forms a single continuous path.
We solve the GTSP using GLKH (http://webhotel4.ruc.dk/~keld/research/GLKH/, accessed on 5 November 2024) as an open source solver [36]. After solving the GTSP, the coverage waypoints P j of visiting the area target f j are obtained. From the sequence planning in the previous section, we obtain the access order of the target T s e q . Let T s e q = { T 1 , T 2 , , T n } represent the sequence in which the targets are accessed, where each T i is either a point target or an area target. P T represents the waypoints associated with target T. For point target m k , the waypoint set P k may consist of a single waypoint. For area target f j , the waypoint set P j consists of multiple waypoints that cover the entire surface area. In summary, the pre-planned waypoints P of the HTSP are obtained by connecting the waypoints of each target T i in the sequence T s e q :
P = i = 1 n P T i

3. Payload Mission Planning

In reconnaissance missions, the performance and efficiency of the UAV’s payload are paramount. The payload mission planning process must therefore account for the specific operational characteristics and constraints. This section integrates payload characteristics to adjust the pre-planned waypoints P. Additionally, obstacle-avoidance waypoints during UAV cruising are generated based on a visibility graph method. The computational workflow for this section is designed to optimize the integration of payload characteristics and waypoint adjustments, as outlined in Figure 1.
Equation (1) is the input for the autonomous mission planning module. It will provide the required payload m o d e (e.g., SAR Beam Focusing or SAR Strip) and i w for each target. We will complete mission planning based on this information.

3.1. Power Instruction

The first step in payload mission planning is managing the power state of the payload, which includes turning it on, standby, etc., depending on the mission’s requirements. The goal here is to ensure that the payload is fully operational when the UAV reaches the target area, thereby avoiding any delays or inefficiencies in data acquisition.
Assuming that the payload’s power-on time is t o n with the input m o d e in (1) and the UAV’s speed is v, we calculate the distance d o n i from the target T i where the power-on command should be issued:
p o n p i d o n = t o n × v
In this formulation, p o n is the waypoint that needs to be inserted, and p i is the position of T i , which may be the point target position or the entry position of an area target. The updated set of waypoints P after inserting p o n can be expressed as:
P = { P T 1 , P T 2 , , p o n , P T i , , P T n }
Similarly, other kinds of commands for the payload can be inserted into the pre-planned waypoint set in the same manner, which will not be elaborated further here. By ensuring that the power command is issued at the correct waypoint, the UAV’s payload will be in the appropriate operational state upon reaching the target.

3.2. Coverage Path Optimization with Payload

Different operating modes of the UAV’s payload have different imaging widths based on factors like resolution and scan mode. By adjusting the offset of the coverage path to match the specific imaging width of the payload in its current mode, we ensure that each pass of the UAV maximizes its coverage area. This minimizes the number of required passes, thereby reducing mission time and energy consumption while ensuring complete coverage without gaps or excessive overlaps.
To adjust the offset of the full coverage path of f j , we need to replace the offset Δ f in Equation (14) with the effective i w of the payload.
We adjust Δ f to i w , so the updated formula for the coverage path lines l k i becomes:
l k i : r = r 0 + i w i w d , i = 0 , 1 , 2 , , n
Based on Equations (14)–(24), we can obtain the adjusted coverage waypoint set P T j for f j . The modified coverage waypoints are then inserted into the pre-planned waypoint set P, as shown in the following equation:
P = { P T 1 , P T 2 , , P T j , P T j + 1 , , P T n }
The payload mission planning process described in this section plays a crucial role in the overall mission planning for reconnaissance fixed-wing UAVs. By carefully managing the power and optimizing the coverage path based on the payload’s characteristics, a UAV can achieve optimal reconnaissance performance, ensuring that all mission objectives are met efficiently and effectively.

3.3. Obstacle Avoidance Based on Visibility Graph

Regardless of whether the target is a point or an area, obstacles may still exist in the region between two targets. Therefore, an obstacle avoidance method based on visibility graphs is adopted. The key steps of the visibility graph algorithm are as shown in Figure 2:
Firstly, each obstacle is represented as a convex polygon. For non-convex obstacles, convex decomposition is performed to divide them into multiple convex components. Subsequently, the vertices of the obstacle polygons are expanded by a safety buffer distance d buffer to account for the UAV’s size and maneuvering limitations:
obs k = { op k n + d buffer n k n op k n obs k }
Here, n k n represents the outward normal vector at vertex op k n .
Next, for the last waypoint p i of the preceding target and the first waypoint p j of the next target in the planned path, we examine whether the line segment p i p j ¯ intersects with any obstacles. The intersection condition can be expressed as:
p i p j ¯ obs k k
The visibility graph G = ( V , E ) is constructed where V contains all obstacle vertices, p i and p j . E contains edges between vertices that are mutually visible.
Two vertices v i and v j are mutually visible if:
v i v j ¯ obs k = k
Then, using Dijkstra’s algorithm on the visibility graph, we find the shortest collision-free path between p i and p j :
P a v o i d k = arg min p G i = 1 n 1 v i + 1 v i
Finally, the obstacle avoidance waypoints are integrated into the final path:
P f i n a l = { P T 1 , P T 2 , , P T k , P a v o i d k , P T k + 1 , , P T n }
This approach ensures safe navigation while maintaining optimal path efficiency. The visibility graph method is particularly effective in environments with multiple convex obstacles, providing guaranteed collision-free paths with minimal computational overhead.

4. Experiments and Discussions

The experimental platform for algorithm validation consisted of a high-performance computing workstation, assembled by Lenovo in Beijing, China. The workstation was equipped with an AMD Ryzen 9 7945HX CPU (16 cores, 2.5 GHz base frequency) and 16 GB DDR4 RAM. The computational environment was implemented in Visual Studio 2022 running on Windows 11. All algorithms were implemented using the Computational Geometry Algorithms Library [37] (CGAL, https://doc.cgal.org/latest/Manual/index.html, accessed on 5 November 2024) in C++, which provides robust implementations of geometric algorithms including polygon operations, convex hulls, and visibility graphs that are essential for our path planning and obstacle avoidance computations. The user interface was developed using the QT framework, providing an interactive visualization environment for mission planning and results analysis. All data were executed on this platform to ensure consistent and reliable performance metrics.

4.1. UI Design

We developed a user-friendly interface for the autonomous mission planning module, as shown in Figure 3, organized into three functional areas from right to left. The right section features input controls for defining mission areas, targets, and no-fly zones, along with options to manage mission parameters such as speed and altitude, and to import/export planning data in XML format. The central section displays a dynamic map with latitude and longitude axes, visually representing the mission area, targets, no-fly zones, and the UAV’s planned waypoints. The left section presents a detailed table of the mission’s waypoints, including their sequence, coordinates, UAV arrival modes, and payload control instructions. This interface streamlines mission setup, visualization, and result analysis.

4.2. Autonomous Mission Planning

BCD stands out for its ability to ensure complete coverage of the area while simplifying the path planning problem. By dividing the workspace into simple, non-overlapping cells, BCD transforms the complex environment into a set of smaller polygons, each free of obstacles. This decomposition not only reduces computational complexity but also enhances the efficiency of path planning algorithms, ensuring that the UAV can systematically cover the entire area with minimal redundant traversal. Figure 4 visually represents this process, highlighting how the region is decomposed into discrete cells around no-fly zones.
In the experimental results depicted in Figure 4a, the BCD method was applied to an area target defined by the vertices ( 50 , 50 ) , ( 50 , 800 ) , ( 800 , 800 ) , and ( 800 , 50 ) , which encompasses two polygonal no-fly zones with vertices ( 148 , 275 ) , ( 418 , 275 ) , ( 621 , 148 ) , ( 148 , 418 ) and ( 270 , 82 ) , ( 523 , 82 ) , ( 523 , 224 ) , ( 270 , 224 ) . These no-fly zones are represented as black polygons within the diagram. The BCD method successfully divided the complex area into seven distinct cells (marked from left to right), each free of no-fly zones. The decomposition process strategically navigated around the no-fly zones. This not only maintains the integrity of the no-fly zones but also maximizes the coverage of the area target by creating well-defined, accessible regions for the UAV to traverse.
Assuming the entry point of the area target in Figure 4b is the top left vertex, the optimal order for accessing these cells based on GTSP is as follows: 6 4 0 1 2 5 3 . Assuming Δ f = 10 , the result of the CPP based on BCD is shown in Figure 4c. Through the above numerical experiments, we have validated its effectiveness.
In the validation phase of the autonomous mission planning module, let us assume a fixed-wing UAV speed of 150 km/h and a flight altitude of 5000 m. The reconnaissance payload requires 70 s from power-on to operational state. The payload has two modes: an SAR Beam Focusing mode and an SAR Strip mode. For the SAR Beam Focusing mode, there are three resolution levels corresponding to three imaging widths, as shown in Table 1. Similarly, the characteristics of the SAR Strip mode are shown in Table 2. To better demonstrate the obstacle avoidance capability of the module in a large-span mission area, we set the d buffer to 2000 m. The input target information includes the required reconnaissance payload mode and resolution for the mission. All position information is represented in latitude and longitude, and the coordinate transformation process during planning will not be elaborated here.
As shown in Figure 5, in the planning map, within a 300 km × 300 km mission area (blue polygon), we input five area targets (black polygons), three no-fly zones (red polygons), five point targets (gray points), the starting point (green point), and the endpoint (blue point).
The proposed module was experimentally validated using the SAR Strip mode.The experiment was divided into two different scenarios. Figure 6 demonstrates the planning results. Firstly, sequence planning calculates the optimal access order, then mission planning optimizes the coverage path based on payload characteristics, and, finally, power instructions are also considered in the final mission instruction set. The following text will analyze these experimental results.
In the first area target scenario, the module successfully adjusted the UAV’s path to accommodate the different resolution requirements of five area targets. For targets 1, 3, and 5, which required high-resolution imaging (0.5), the UAV followed a finer, closer-offset path to ensure detailed coverage. Target 2, requiring medium resolution (1.0), had a lower path density. For target 4, with the lowest resolution requirement (3.0), the module optimized the path for broader coverage with minimal overlap. In the second scenario, the experiment focused on processing point target scenes, where the resolution requirement for all five point targets was uniformly set to 0.5. This scenario was mainly used to verify the module’s switching in various mission scenarios. Figure 7a illustrates the module output path. For the area target scenario, the module successfully adapts to varying resolution requirements, while the point target scenario demonstrates the module’s effective switching between scenarios. Figure 7b illustrates an obstacle avoidance method based on visibility graphs. By expanding obstacle vertices according to the d buffer , a visibility graph is constructed with waypoint No. 73 (lon: −59.5076; lat: −34.7782) as the starting point and waypoint No. 75 (lon: −58.8323; lat: −37.0782) as the endpoint. Utilizing Dijkstra’s algorithm, the shortest collision-free path is identified, successfully generating waypoint No. 74 (lon: −59.3972; lat: −36.1817) as the obstacle avoidance waypoint. The distance between this waypoint and the closest vertex of the rectangular obstacle (longitude: −59.368118; latitude: −36.192308) satisfies the requirement d buffer . This method ensures safe and efficient navigation.
As shown in the mission instruction list on the left side of Figure 7c, the module issued instruction No. 25 for the reconnaissance. Notably, the module inserted instruction No. 24 to power on the payload in advance, ensuring that it was fully operational upon reaching the target. To validate the computational efficiency of the proposed algorithm, we conducted multiple groups of test experiments. Each dataset consisted of 10 targets and three obstacles distributed across a 300 km × 300 km mission area. As shown in Figure 8, the experimental results demonstrate that the proposed method consistently completed calculations within 0.5 s across all test scenarios. The computation time, consistently below 500 ms, ensures compliance with the stringent operational requirements of fixed-wing UAVs.

5. Conclusions

This paper presented a comprehensive approach to autonomous mission planning for fixed-wing UAVs, specifically tailored to multiscenario reconnaissance missions. By addressing the limitations of existing UAV planning methods, which often overlook the integration of payload characteristics, we developed an advanced autonomous mission planning module that combines flight path planning and payload planning.
The proposed path planning strategy, grounded in the HTSP, effectively determines the optimal sequence for accessing reconnaissance targets and planning entry waypoints. The GTSP further enhances the coverage path planning, ensuring thorough reconnaissance even in complex environments with no-fly zones.
Our payload mission planning methodology meticulously considers key payload parameters such as scan resolution, imaging width, and modes. This ensures that each mission instruction is optimized to meet the payload’s performance requirements, thereby maximizing reconnaissance effectiveness.
Experiments demonstrated the practical applicability of the module, allowing for intuitive verification and validation of its effectiveness. Overall, the results affirm the superiority of our integrated mission planning module, providing a robust solution for efficient and effective UAV reconnaissance in diverse scenarios. Future work could extend this framework to accommodate additional mission constraints and enhance real-time adaptability in dynamic environments.

Author Contributions

Conceptualization, B.C., J.Y. and Z.Z.; methodology, B.C. and J.Y.; software, J.Y., J.L. and R.L.; writing—review and editing, B.C. and J.Y.; visualization, J.L.; supervision, Z.Z.; project administration, R.L. and Z.Z.; funding acquisition, Z.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the National Natural Science Foundation of China under Grant No. (42474017; 42074038) and, in part, by the System of Systems and Artificial Intelligence Laboratory pioneer fund grant.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

Authors Bei Chen and Rui Lai were employed by the company AVIC (Chengdu) Unmanned Aerial Vehicle Systems Co., Ltd. The remaining authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

References

  1. Sonkar, S.; Kumar, P.; Philip, D.; Ghosh, A.K. Low-cost smart surveillance and reconnaissance using VTOL fixed wing UAV. In Proceedings of the 2020 IEEE Aerospace conference, Big Sky, MT, USA, 7 March 2020; pp. 1–7. [Google Scholar]
  2. Zhang, J.; Huang, H. Occlusion-aware UAV path planning for reconnaissance and surveillance. Drones 2021, 5, 98. [Google Scholar] [CrossRef]
  3. Ranasinghe, N.D.; Gunawardana, W.A.D.L. Development of gasoline-electric hybrid propulsion surveillance and reconnaissance VTOL UAV. In Proceedings of the 2021 IEEE International Conference on Robotics, Automation and Artificial Intelligence, Hong Kong, China, 21 April 2021; pp. 63–68. [Google Scholar]
  4. Liao, S.L.; Zhu, R.M.; Wu, N.Q.; Shaikh, T.A.; Sharaf, M.; Mostafa, A.M. Path planning for moving target tracking by fixed-wing UAV. Def. Technol. 2020, 16, 811–824. [Google Scholar] [CrossRef]
  5. Yang, L.; Liu, Z.; Wang, X.; Yu, X.; Wang, G.; Shen, L. Image-based visual servo tracking control of a ground moving target for a fixed-wing unmanned aerial vehicle. J. Intell. Robot. Syst. 2021, 102, 1–20. [Google Scholar] [CrossRef]
  6. Sun, Z.; Garcia de Marina, H.; Anderson, B.D.; Yu, C. Collaborative target-tracking control using multiple fixed-wing unmanned aerial vehicles with constant speeds. J. Guid. Control. Dyn. 2021, 44, 238–250. [Google Scholar] [CrossRef]
  7. Yang, Y.; Leeghim, H.; Kim, D. Dubins Path-Oriented Rapidly Exploring Random Tree* for Three-Dimensional Path Planning of Unmanned Aerial Vehicles. Electronics 2022, 11, 2338. [Google Scholar] [CrossRef]
  8. Aiello, G.; Valavanis, K.P.; Rizzo, A. Fixed-wing uav energy efficient 3d path planning in cluttered environments. J. Intell. Robot. Syst. 2022, 105, 60. [Google Scholar] [CrossRef]
  9. Machmudah, A.; Shanmugavel, M.; Parman, S.; Manan, T.S.A.; Dutykh, D.; Beddu, S.; Rajabi, A. Flight trajectories optimization of fixed-wing UAV by bank-turn mechanism. Drones 2022, 6, 69. [Google Scholar] [CrossRef]
  10. Cui, Q. Multi-target points path planning for fixed-wing unmanned aerial vehicle performing reconnaissance missions. In Proceedings of the 5th International Conference on Information Science, Electrical, and Automation Engineering, Wuhan, China, 24 March 2023; Volume 12748, pp. 713–723. [Google Scholar]
  11. Ding, Z.; Huang, Y.; Yuan, H.; Dong, H. Introduction to reinforcement learning. In Deep Reinforcement Learning: Fundamentals, Research and Applications; Dong, H., Ding, Z., Zhang, S., Eds.; Springer: Singapore, 2020; pp. 47–123. [Google Scholar]
  12. Chen, J.; Ling, F.; Zhang, Y.; You, T.; Liu, Y.; Du, X. Coverage path planning of heterogeneous unmanned aerial vehicles based on ant colony system. Swarm Evol. Comput. 2022, 69, 101005. [Google Scholar] [CrossRef]
  13. Theile, M.; Bayerlein, H.; Nai, R.; Gesbert, D.; Caccamo, M. UAV coverage path planning under varying power constraints using deep reinforcement learning. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems, Las Vegas, NV, USA, 24 October 2020; pp. 1444–1449. [Google Scholar]
  14. Jia, Y.; Zhou, S.; Zeng, Q.; Li, C.; Chen, D.; Zhang, K.; Liu, L.; Chen, Z. The UAV path coverage algorithm based on the greedy strategy and ant colony optimization. Electronics 2022, 17, 2667. [Google Scholar] [CrossRef]
  15. Majeed, A.; Hwang, S.O. A multi-objective coverage path planning algorithm for UAVs to cover spatially distributed regions in urban environments. Aerospace 2021, 11, 343. [Google Scholar] [CrossRef]
  16. Vazquez-Carmona, E.V.; Vasquez-Gomez, J.I.; Herrera-Lozada, J.C.; Antonio-Cruz, M. Coverage path planning for spraying drones. Comput. Ind. Eng. 2022, 168, 108125. [Google Scholar] [CrossRef] [PubMed]
  17. Galceran, E.; Carreras, M. A survey on coverage path planning for robotics. Robot. Auton. Syst. 2013, 61, 1258–1276. [Google Scholar] [CrossRef]
  18. Vasquez-Gomez, J.I.; Marciano-Melchor, M.; Valentin, L.; Herrera-Lozada, J.C. Coverage path planning for 2d convex regions. J. Intell. Robot. Syst. 2020, 97, 81–94. [Google Scholar] [CrossRef]
  19. Tan, C.S.; Mohd-Mokhtar, R.; Arshad, M.R. A comprehensive review of coverage path planning in robotics using classical and heuristic algorithms. IEEE Access 2021, 9, 119310–119342. [Google Scholar] [CrossRef]
  20. Barrientos, A.; Colorado, J.; Cerro, J.D.; Martinez, A.; Rossi, C.; Sanz, D.; Valente, J. Aerial remote sensing in agriculture: A practical approach to area coverage and path planning for fleets of mini aerial robots. J. Field Robot. 2011, 28, 667–689. [Google Scholar] [CrossRef]
  21. Hasan, K.M.; Reza, K.J. Path planning algorithm development for autonomous vacuum cleaner robots. In Proceedings of the 2014 International Conference on Informatics, Electronics & Vision, Dhaka, Bangladesh, 23 May 2014; pp. 1–6. [Google Scholar]
  22. Bähnemann, R.; Lawrance, N.; Chung, J.J.; Pantic, M.; Siegwart, R.; Nieto, J. Revisiting boustrophedon coverage path planning as a generalized traveling salesman problem. In Proceedings of the Field and Service Robotics: Results of the 12th International Conference, Tokyo, Japan, 29 August 2019; pp. 277–290. [Google Scholar]
  23. Kumar, K.; Kumar, N. Region coverage-aware path planning for unmanned aerial vehicles: A systematic review. Phys. Commun. 2023, 59, 102073. [Google Scholar] [CrossRef]
  24. Choset, H.; Pignon, P. Coverage path planning: The boustrophedon cellular decomposition. In Proceedings of the Field and Service Robotics, Canberra, Australia, 8–10 December 1997; pp. 203–209. [Google Scholar]
  25. Choset, H. Coverage of known spaces: The boustrophedon cellular decomposition. Auton. Robot. 2000, 9, 247–253. [Google Scholar] [CrossRef]
  26. Apostolidis, S.D.; Kapoutsis, P.C.; Kapoutsis, A.C.; Kosmatopoulos, E.B. Cooperative multi-UAV coverage mission planning platform for remote sensing applications. Auton. Robot. 2022, 46, 373–400. [Google Scholar] [CrossRef]
  27. Stecz, W.; Gromada, K. UAV mission planning with SAR application. Sensors 2020, 4, 1080. [Google Scholar] [CrossRef]
  28. Zhang, Y.; Chen, Z.; Yan, Y.; Jiang, F.; Gao, X. Research on single target cognitive electronic reconnaissance strategy for unmanned aerial vehicle. IET Radar Sonar Navig. 2023, 11, 1711–1727. [Google Scholar] [CrossRef]
  29. Stecz, W.; Gromada, K. Determining UAV flight trajectory for target recognition using EO/IR and SAR. Sensors 2020, 20, 5712. [Google Scholar] [CrossRef] [PubMed]
  30. Asiyabi, R.M.; Ghorbanian, A.; Tameh, S.N.; Amani, M.; Jin, S.; Mohammadzadeh, A. Synthetic aperture radar (SAR) for ocean: A review. IEEE J. Sel. Top. Appl. Earth Obs. Remote. Sens. 2023, 16, 9106–9138. [Google Scholar] [CrossRef]
  31. Luomei, Y.; Xu, F. Segmental aperture imaging algorithm for multirotor UAV-borne MiniSAR. IEEE Trans. Geosci. Remote Sens. 2023, 61, 1–8. [Google Scholar] [CrossRef]
  32. Zhou, Y.; Wang, W.; Chen, Z.; Wang, P.; Zhang, H.; Qiu, J.; Zhao, Q.; Deng, Y.; Zhang, Z.; Yu, W.; et al. Digital beamforming synthetic aperture radar (DBSAR): Experiments and performance analysis in support of 16-channel airborne X-band SAR data. IEEE Trans. Geosci. Remote Sens. 2020, 59, 6784–6798. [Google Scholar] [CrossRef]
  33. García-Fernández, M.; Álvarez-Narciandi, G.; López, Y.; Las-Heras, F. Array-based ground penetrating synthetic aperture radar on board an unmanned aerial vehicle for enhanced buried threats detection. IEEE Trans. Geosci. Remote Sens. 2023, 61, 1–18. [Google Scholar] [CrossRef]
  34. Yuan, Y.; Cattaruzza, D.; Ogier, M.; Semet, F. A branch-and-cut algorithm for the generalized traveling salesman problem with time windows. Eur. J. Oper. Res. 2020, 286, 849–866. [Google Scholar] [CrossRef]
  35. Nourmohammadzadeh, A.; Sarhani, M.; Voß, S. A matheuristic approach for the family traveling salesman problem. J. Heuristics 2023, 29, 435–460. [Google Scholar] [CrossRef]
  36. Helsgaun, K. Solving the equality generalized traveling salesman problem using the Lin–Kernighan–Helsgaun Algorithm. Math. Prog. Comp. 2015, 7, 269–287. [Google Scholar] [CrossRef]
  37. Fabri, A.; Pion, S. CGAL: The computational geometry algorithms library. In Proceedings of the 17th ACM SIGSPATIAL International Conference on Advances in Geographic Information Systems, Seattle, WA, USA, 4–6 November 2009; pp. 538–539. [Google Scholar]
Figure 1. Computational workflow for UAV payload mission planning.
Figure 1. Computational workflow for UAV payload mission planning.
Sensors 25 01176 g001
Figure 2. Visualization of the visibility graph algorithm for UAV obstacle avoidance. The algorithm identifies potential intersections between the planned path segment p i p j ¯ , represented by the red line segment, and obstacle polygons. Obstacles are expanded by a buffer distance d buffer to ensure safety, and alternate paths, such as through p avoid k , are generated to bypass obstacles, as illustrated by the green line.
Figure 2. Visualization of the visibility graph algorithm for UAV obstacle avoidance. The algorithm identifies potential intersections between the planned path segment p i p j ¯ , represented by the red line segment, and obstacle polygons. Obstacles are expanded by a buffer distance d buffer to ensure safety, and alternate paths, such as through p avoid k , are generated to bypass obstacles, as illustrated by the green line.
Sensors 25 01176 g002
Figure 3. UI for autonomous mission planning module.
Figure 3. UI for autonomous mission planning module.
Sensors 25 01176 g003
Figure 4. Area target with no-fly zones and its Boustrophedon Cell Decomposition. (a) An area target with no-fly zones. (b) Boustrophedon Cell Decomposition of an area target with no-fly zones.The area target is decomposed into 6 cells without no-fly zones, marked from 0 to 6 respectively. (c) Results of coverage path planning with an area target.
Figure 4. Area target with no-fly zones and its Boustrophedon Cell Decomposition. (a) An area target with no-fly zones. (b) Boustrophedon Cell Decomposition of an area target with no-fly zones.The area target is decomposed into 6 cells without no-fly zones, marked from 0 to 6 respectively. (c) Results of coverage path planning with an area target.
Sensors 25 01176 g004
Figure 5. Planning map.
Figure 5. Planning map.
Sensors 25 01176 g005
Figure 6. Planning results of autonomous mission planning module.
Figure 6. Planning results of autonomous mission planning module.
Sensors 25 01176 g006
Figure 7. Path planning analysis, visibility graph-based obstacle avoidance, and payload power instruction output. (a) Path planning for different target scenarios, illustrating the planned waypoint set under varying conditions. (b) Visibility graph-based obstacle avoidance, demonstrating the generated path that navigates around no-fly zones and obstacles. (c) The output of payload power instructions, showing the power-on and work instructions of the payload during the mission. (a) Path planning for different targets. (b) Visibility graph-based obstacle avoidance for path planning. (c) The output of payload power instructions.
Figure 7. Path planning analysis, visibility graph-based obstacle avoidance, and payload power instruction output. (a) Path planning for different target scenarios, illustrating the planned waypoint set under varying conditions. (b) Visibility graph-based obstacle avoidance, demonstrating the generated path that navigates around no-fly zones and obstacles. (c) The output of payload power instructions, showing the power-on and work instructions of the payload during the mission. (a) Path planning for different targets. (b) Visibility graph-based obstacle avoidance for path planning. (c) The output of payload power instructions.
Sensors 25 01176 g007
Figure 8. Comparison of algorithm execution times under three different test datasets. The results demonstrate that the computation time is within 0.5 s. (a) Time consumption results of the first set of test data. (b) Time consumption results of the second set of test data. (c) Time consumption results of the third set of test data.
Figure 8. Comparison of algorithm execution times under three different test datasets. The results demonstrate that the computation time is within 0.5 s. (a) Time consumption results of the first set of test data. (b) Time consumption results of the second set of test data. (c) Time consumption results of the third set of test data.
Sensors 25 01176 g008
Table 1. The characteristics of the SAR Beam Focusing mode.
Table 1. The characteristics of the SAR Beam Focusing mode.
Default Work AltitudeImaging ResolutionRangeImaging Width
5000 m0.5 m16–80 km5 km × 5 km
0.3 m12–60 km3 km × 3 km
0.1 m12–30 km1 km × 1 km
Table 2. The characteristics of the SAR Strip mode.
Table 2. The characteristics of the SAR Strip mode.
Default Work AltitudeImaging ResolutionRangeImaging Width
5000 m5 m72–120 km405 km
1 m60–100 km203 km
0.5 m48–80 km12 km
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Chen, B.; Yan, J.; Zhou, Z.; Lai, R.; Lin, J. Autonomous Mission Planning for Fixed-Wing Unmanned Aerial Vehicles in Multiscenario Reconnaissance. Sensors 2025, 25, 1176. https://doi.org/10.3390/s25041176

AMA Style

Chen B, Yan J, Zhou Z, Lai R, Lin J. Autonomous Mission Planning for Fixed-Wing Unmanned Aerial Vehicles in Multiscenario Reconnaissance. Sensors. 2025; 25(4):1176. https://doi.org/10.3390/s25041176

Chicago/Turabian Style

Chen, Bei, Jiaxin Yan, Zebo Zhou, Rui Lai, and Jiejian Lin. 2025. "Autonomous Mission Planning for Fixed-Wing Unmanned Aerial Vehicles in Multiscenario Reconnaissance" Sensors 25, no. 4: 1176. https://doi.org/10.3390/s25041176

APA Style

Chen, B., Yan, J., Zhou, Z., Lai, R., & Lin, J. (2025). Autonomous Mission Planning for Fixed-Wing Unmanned Aerial Vehicles in Multiscenario Reconnaissance. Sensors, 25(4), 1176. https://doi.org/10.3390/s25041176

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop