1. Introduction
Due to recent advances in communication, sensing and battery technologies, Unmanned Aerial Vehicles (UAVs) have drawn much attention for both military and civilian applications. Due to their portability and flexibility, UAVs are employed for numerous civilian applications, including industrial monitoring, scientific data collection and public safety (search and rescue). Soon, autonomous aircraft equipped with various sensors will be routinely surveilling our cities, neighborhoods and rural areas. They promise far reaching benefits for the study and understanding of public collaboration systems.
There are two main categories of UAVs: fixed-wing aircraft and multi-rotor vehicles. Compared with multi-rotor vehicles, fixed-wing aircraft are more advanced in many respects: they tend to be more stable in the air in the face of both piloting and technical errors as they have natural gliding capabilities even without power, and they are able to travel longer distances on less power. More importantly, they have the advantages of being able to fly at high speeds for a long time using a simpler structure. These characteristics make fixed-wing vehicles still widely popular, despite requiring a runway or launcher for takeoff and being unable to hover. For these reasons, we consider the path planning problem for fixed-wing UAVs in this work.
An important technical problem must, however, be addressed: How can we plan feasible and optimal paths that are effective are increasing the mission success rates and reducing the time taken? Path planning aims to determine a path from the initial position to the final position through a complicated space with or without obstacles. This is still an open problem in the field of autonomous systems research as it involves physical constraints due to the UAVs themselves and constraints due to their operating environment, as well as other operational requirements.
Several quintessential methods have been developed for path planning such as Voronoi diagrams [
1], triangular-cell-based maps [
2], as well as related grid-like maps [
3,
4], the potential function method [
5], the A* algorithm [
6,
7], probability roadmaps [
8], evolutionary algorithms [
9,
10,
11,
12] and mixed integer-linear programming [
13,
14]. Although these methods can provide optimal or near-optimal paths that pass through all predefined waypoints, they cannot guarantee smoothness, i.e., curvature continuity. Curvature discontinuities would cause sudden changes in the vehicle’s heading and threaten its safety. To generate suitable paths for UAVs, several problems need to be tackled.
- (1)
Path curvature continuity: This directly influences the vehicles’ aerodynamics and kinematics.
- (2)
Path optimization: We want to find the shortest path that passes through all of the expected waypoints. This is especially critical for missions such as reconnaissance and aerial delivery where vehicles are expected to fly over the specified target precisely, as any deviation would cause target information lost during reconnaissance and drop failures in transportation tasks.
- (3)
Local path adjustment: Dynamic environments require path replanning, which would consequently consume additional time. Accordingly, the planning method should be able to support local modifications.
The construction of feasible paths has been actively investigated in robotic research fields, because non-smooth motions can cause wheel slippage and degrade the robots’ dead-reckoning abilities [
15]. Dubins curves are one practical method [
16,
17,
18], as they can give the shortest path between given initial and final points with a fixed change rate of turn [
16]. In these algorithms, two points are connected by concatenating arcs and tangents. Sahingoz et al. [
18] and Shanmugavel et al. [
19] apply Dubins curves to UAV path planning in 2D space after task allocation. Dubins curves have been extended to include other spline curves such as helix to generate more complex vehicle trajectory models in 3D space [
17,
20]. However, there are still curvature discontinuities at the junctions between lines and arcs, leading to yaw angle errors for UAVs. As a result, the corresponding applications are limited to straight flights.
To deal with the curvature discontinuity problem, two categories of curves are utilized in [
21,
22,
23,
24,
25,
26]. The first category involves parameterizing the curvature by arc length using, for example, clothoids [
21,
22]. Clothoid pairs can provide the shortest curves for a given turn angle [
27]. However, there is no closed-form expression for position along the path or its approximation. Moreover, look-up tables are usually required, increasing the operational complexity. The second category can provide closed-form solutions, using, for example, B-splines, Bezier curves or spatial Pythagorean hodographs [
23,
24,
25,
27,
28,
29,
30]. These curves are used for trajectory generation for both UAVs [
23,
24] and autonomous robots [
25,
28]. However, path curvature is a high-order function of curve parameters, and it is a formidable challenge to analyze its monotonicity. Generated paths have continuous curvature when using Bezier curves [
31] or B-splines [
32], but little attention has been given to the maximum curvature constraint. Although it has been demonstrated that curvature extrema can be obtained numerically for any planar cubic curve, this might be a challenge for parametric polynomial curves [
29,
33], since it is difficult to solve the formulated curvature extremum model. An objective function has been designed to search for proper Bezier curve parameters that satisfy the maximum curvature constraint, but the optimization problem remains unsolved [
34]. Additionally, combined Bezier curves can be used to generate continuous curvature paths with bounded curvature extrema in both 2D and 3D space [
24]. Shanmugavel et al. [
30] have proposed a Pythagorean hodograph curve for 3D path planning, achieving bounded curvature and equal path lengths. Unfortunately, the generated path only passes through some of the waypoints, accordingly leading to failure of some specified tasks.
Despite all of these efforts, the challenge of generating feasible and optimal trajectories has been partially solved in the literature above. Furthermore, local path adjustment has been ignored, which is important in real applications. Replanning the whole path would be inefficient due to additional time and energy required. By contrast, local adjustment can reduce replanning complexity because the adjustment is used only where needed. Parametric curves with local adjustment, including B-splines and Beta-splines, can potentially be used for path planning. In particular, the construction of geometric continuous Beta-splines has been achieved by DeRose T D et al. In our work, the path planning problem is solved using a three-stage decomposition, which allows curvature continuity and curvature adjustment to be completely independent of each other. This strategy was inspired by the approach in [
35], where circular orbits and Bezier curves are concatenated to create more complicated paths.
The objective of this paper is to develop path planning strategies that explicitly account for curvature and waypoint constraints. Previous work has primarily addressed path feasibility, whereas in this paper, we also consider path accuracy. In this paper, a continuous-curvature and bounded path planning algorithm for fixed-wing UAVs is proposed to solve the problem of passing through all of the waypoints under aerodynamic constraints. To this end, a parametric Catmull–Rom curve is employed.
The specific contributions of this paper are given below.
- (1)
A path planning framework is proposed to generate a feasible path that satisfies both curvature continuity and upper bound constraints.
- (2)
Path accuracy, which is absolutely necessary for aerial photography and air drop, is explicitly satisfied using the path planning algorithm.
- (3)
Geometric shaping of the replanned path can be systematically performed with the designed minimum curvature circle transition mechanism.
- (4)
The proposed path planning algorithm can also be able to solve obstacle avoidance problems to some extent.
The rest of this paper is organized as follows.
Section 2 presents the problem formulation. In
Section 3, a three-stage trajectory architecture is presented. In
Section 4, a cross-value-based interpolation algorithm and a key-point shift algorithm are elaborated and the planar transition algorithm introduced. In
Section 5, a path replanning algorithm using minimum curvature circle transitions is proposed. Simulation and experimental results are shown in
Section 6, followed by the conclusion in
Section 7.
2. Problem Statement
Let be a sequence of waypoints in a 2D space returned by a higher planner. The path planning problem is to find a mission flight trajectory that fits all of the waypoints smoothly, satisfying curvature continuity and maximum curvature constraints.
For a feasible path curve, the curvature continuity and maximum curvature requirements must be satisfied simultaneously. Curvature discontinuity would lead to infinite changes in lateral acceleration, which can obviously not be allowed. Likewise, the curvature is proportional to the centripetal force at fixed velocity, and thus, unbounded curvature could result in roll angles that exceed the safety limits.
The smoothness of curve junctions can be measured by geometric and parametric continuity. Different orders of smoothness in terms of geometric and parametric continuity are defined in [
36].
Parametric continuity: Let P(
,
:s) and Q(
,
:t) be parametric curves, such that
. They meet at
m with
k-th order parametric continuity if:
Geometric continuity: Let P(,:s) and Q(,:t) be parametric curves, such that . They meet at m with k-th order geometric continuity if the natural parameterizations of P and Q meet at m with parametric continuity.
These definitions are also used in this paper. Barsky et al. [
36] point out that parametric continuity prevents parameterizations from generating geometrically smooth curves due to the strict constraints imposed by the derivatives. By contrast, geometric continuity accommodates differences between the parameterizations of adjoining curves, and thus, it is used to smooth the piecewise path in our work.
The UAV navigation limitations are due to its own kinematic constraints. As it has been widely proven that vertical motions consume additional energy, we also assume that the UAV is flying at constant altitude. The aerodynamics features of a fixed-wing UAV include lift force
L and air friction
D.
where
is the air density,
V is the flying speed,
S is the wing area and
represents the lift coefficient.
where
is the air density,
V is the flying speed,
S is the maximum section area of an UAV and
represents the resistance coefficient.
From the above two equations, we can see that the flying speed directly determines the lift force and air friction for a UAV under stable atmospheric conditions. In parallel, acceleration is generated from the corresponding component force, and this in turn changes the velocity of a UAV. Due to the designs themselves, fixed-wing UAVs have a minimum speed (the stall speed ), below which they risk falling out of the sky. In addition, UAVs are limited to a maximum speed of by power constraints. In practice, parameters including air density, wing area, lift coefficient, the maximum section area and the resistance coefficient were fixed. Thus, the dynamic constraint is the velocity: .
To acquire the relation between curvature, velocity and lateral acceleration, a typical circular motion model is used to illustrate the turning motion for fixed-wing UAVs.
where
F represents the centripetal force,
v is the UAV’s velocity and
R denotes the turning radius. Equation (
4) can be further rewritten as:
.
Since the curvature is inversely proportional to the turning radius
R, the relation among curvature, velocity and lateral can be described as follows:
Due to the total centripetal force, which keeps constant during the turning, the curvature gets its minimum value (
) when the flying speed reaches the extreme value (
). Consequently, the relation between maximum curvature, maximum velocity and lateral acceleration is:
As far as the dynamics is concerned, (6) shows that the curvature is directly proportional to the vehicle’s lateral acceleration. The maximum curvature (
) is inversely proportional to the minimum curvature radius (
) of the curves that it is able to follow. A path is valid if the curvature is smaller than the specified maximum value,
where
denotes the maximum curvature determined by the UAV’s dynamic constraints.
The path planning problem in this paper is independent of the UAVs’ dynamic models. The single or double integrator model is commonly used to characterize an individual UAV for state analysis. Since the power for a fixed-wing UAV is supplied by motors and direct user interactions are operations on the motor speed that change the state of a UAV, consequently, it is difficult to control the velocity and acceleration directly in engineering. For fixed-wing UAVs, which have a six degree of freedom movement, translational and rotational motions are achieved by adjusting propeller speed and the servomotor controller. Although different dynamic models are employed, the aerodynamic constraints are identical. To be specific, the curvature must be continuous and bounded in the 2D environment.
3. Three-Stage Trajectory Architecture
To deal with problems involving planning, a three-stage path planning algorithm with a transition selection mechanism for piecewise paths is proposed in this paper. The operational workflow of this algorithm is presented in
Figure 1.
Our algorithm has two key components: curvature smoothing and curvature constraining. The Catmull-Rom curve is advanced in its local-control ability and owns the property that it passed through the control points. Thus, a Catmull-Rom curve is used to fit the waypoints firstly, to achieve path accuracy. Then, an optimal position or key point is extrapolated to smooth the curvature on the base of Phase 1. After that, to ensure that the UAV flies over each waypoint obeying the aerodynamic constraints, a minimum curvature circle transition scheme is used to replan those piecewise curves whose curvature exceeds the upper boundary.
Obstacle avoidance increases complexity for path planning and leads to path replanning. For off-line path planning, path curves should be designed to avoid obstacles using their prior knowledge such as positions and shapes. This results in constraints on path curves and consequently increases the algorithm complexity of path planning. As for on-line path planning, new paths must be planned rapidly to avoid dynamic obstacles, meaning that the whole path or local path should be replanned.
Our method was advanced in the organic coordination of path planning and obstacle avoidance. The method proposed can potentially solve some obstacle avoidance problems, while generating a continuous curvature and bounded path that passes through all waypoints.
In fact, the obstacle avoidance mechanism in
Figure 2 is to navigate around obstacles by designing a path via path re-planning. By adding or moving a waypoint, the predefined path is locally changed. This path re-planning helps to solve the obstacle avoidance problem at the path level.
Specific to multiple waypoint path planning, there are mainly two types of obstacles as shown in
Figure 2.
In the first scenario, we believe the collision avoidance problem can be solved by our proposed optimal interpolation method as demonstrated in
Figure 2a. By adding a new waypoint, the path is replanned, and UAVs navigate around obstacles successfully. The research background of this paper is mainly ground observation using fixed wings UAVs where aeronautics and astronautic sensors are equipped on the vehicles for surface and human activities explorations. Under such background, the obstacle avoidance problem shown in
Figure 2b can be tackled by driving the UAVs to fly over some waypoints. Although this operation results in range deviation between the flight path and waypoint and consequently reduces image quality, we believe that this quality decrease is allowable compared with the UAVs’ safety. Additionally, a PTZ (pan/tile/zoom) camera can also help to eliminate or mitigate the above negative influence.
4. Continuous Path Smoothing with Multiple Waypoints
It has been proven that Beta-constraints are necessary and sufficient conditions for
continuity [
37]. As an example, the Beta-constraints for
continuity take the following form:
where
r and
q are abbreviations for the parametric curves
and
and
and
are real numbers to represent the linear relationship between the deviation of parameter curves (
can take arbitrary values, but
must be positive).
Our goal has been to provide a path curve that passes through all waypoints and simultaneously satisfies Beta-constraints. It would be elegant to obtain an algebraic solution demonstrating the curve’s adequacy and completeness, but it is arduous to solve sets of second order differential equations with two degrees of freedom since it is formidably difficult to find closed-form solutions. We instead present a practical algorithm based on the idea that a geometric method can be used to design a quantic interpolating spline, which is a subclass of the Catmull–Rom splines with two shape control parameters [
38]. In this section, a Catmull–Rom-based continuous-curvature condition is derived, and a relevant path smoothing algorithm is presented.
4.1. Curvature Continuity Condition
In order to get a better and clearer understanding of the work below, the construction method of the Catmull–Rom curve is briefly introduced in this section. The method consists of three parts: set shape parameters, calculate Bezier polygon, determine Bezier control points. The effect of shape parameters was studied in [
38], and they were recommended to be set as
and
. After iteration calculation, the polygon of an auxiliary Bezier curve was figured out. Finally, the expected Bezier control points were determined by the linear weight of the auxiliary Bezier polygon.
For predefined waypoints, curvature discontinuities may exist at junction points, as shown in
Figure 3. Further investigation indicates that the shape parameters and positions of the corresponding waypoints are the decisive factors in determining the degree of discontinuity. For simplicity’s sake, we set the shape parameters as follows:
and
. It should be noted that although the results in Equation (
9) would change when the parameters are different, the curvature smoothing algorithm proposed still holds.
According to the Catmull–Rom curve construction method given in [
38], the curvature change at the point
is given by:
To ensure curvature continuity, the above condition is used to calculate point position in optimal interpolation and key-point shift algorithms.
4.2. Path Smoothing Algorithm
The curvature continuity condition essentially puts constraints on the relative positions of waypoints. If the local distribution of the original points is properly adjusted, curvature continuity can be achieved. Although (
9) is the strict mathematical condition for curvature continuity, this theoretical requirement is difficult to satisfy in practice due to project errors such as measurement or mechanical errors. Thus, we regard the curve as continuous as long as the curvature change is less than a given limit
. Various tasks have different requests with respect to time cost. For example, a loose time constraint is needed in aerial photography tasks. By contrast, missions such as rescue and reconnaissance require that the time taken must be as little as possible. To meet different demands on time cost while satisfying the continuous-curvature condition, two algorithms (optimal interpolation and key-point shift algorithm) were proposed.
The core idea of the optimal interpolation algorithm is to find a reasonable position to insert a new waypoint. Equation (
9) shows that a new waypoint would influence the curvature of five neighboring junctions. Consequently, the goal is to find a point that makes the associated curvature changes tend to zero. By considering how the control points of nearby piecewise curves are affected by the inserted waypoint, the optimization objective is to minimize the length of these curves. As a result, the proposed algorithm solves the following optimization problem.
where
represents the related path length and
denotes a user-defined continuity threshold. Numerical methods such as steepest descent and Newton’s method are usually employed to solve such optimization problems, but in practice, the integral for calculating the arc length cannot be solved. By contrast, the Gaussian quadrature method only needs the polynomial form of the integral and selects the expected number of points on the integral interval, reducing the computational complexity dramatically. To increase the computational efficiency, both the Gaussian quadrature method and a Genetic Algorithm (GA) are adopted. The input and output of the algorithm are the set of waypoints and the coordinates of the objective point, respectively.The main steps of the optimal interpolation are described in
Figure 4.
The optimal interpolation algorithm mainly consists of two phases: construct a cost function and solve the optimization problem. Since the task cycle is a key factor that determines the optimization of flight paths, the path length has also been taken into consideration in the cost function. To obtain the explicit formulation of the cost involved, numerical computation is conducted via Gaussian Quadrature (GQ). Considering that the lengths of adjacent piecewise paths are effected by the newly-added waypoint, those related sequence numbers of waypoints are figured out firstly. Then, the length of each segment is estimated by GQ. As for the curvature change value, the result from Equation (
9) is used.
The GA algorithm that was used to solve the optimal interpolation problem was a function encapsulated in a toolbox by MATLAB. The function is: X = ga(fitnessfcn,nvars,A,b,Aeq,beq,LB,UB). In the GA algorithm, the input is curve length and curvature change values with corresponding weight coefficients, and the output is the coordinate of the objective point. Some key parameters in the optimal interpolation algorithm are given as follows: is the sequence number of the point needed to be interpolated; is the total number of piecewise curve; represents the number of segments that are located ahead of the interpolated point; denotes the number of segments that are located behind the interpolated point; are the start and end sequence number of the points affected by the interpolation operations, respectively; is the length of the new waypoint set; is the total path length related to the interpolation point; are the control point of Bezier curves; and is the total curvature change value.
The key idea of the key-point shift algorithm is to displace as few waypoints as possible and then replan the trajectory using these new points. Due to curve shape changes, the two proposed algorithms both result in path length increment. Thus, curvature smoothing and curve length are two main factors considered in path smoothing. Consequently, we set the curvature change value as the constraint and the curve length as a target, as shown in Equation (
10), in both the optimal interpolation and key-point shift algorithms. The optimization problem can be formulated as in Equation (
10).
To solve the above optimization problem, weight coefficients (, ) were set for the curvature change value and path length, respectively, in the optimal interpolation and key-point shift algorithms.
However, curvature continuity is achieved through curve shape changes by the added piecewise path in the optimal interpolation algorithm, while the key-point shift algorithm is to displace as few waypoints as possible, avoiding the introduction of new waypoints. This results in a much greater increment in path length for the optimal interpolation algorithm. To obtain satisfactory results, different weight coefficient were assigned ( = 800−3000, = 500−3000) in the optimal interpolation algorithm and ( = 800−3000, = 100−500) in the key point shift algorithm. The results of and are empirical values based on a large number of numerical experiments.
5. Minimum Curvature Circle Transition
To ensure path feasibility for a given UAV, the curve () must fulfill certain aerodynamic constraints. The maximum curvature () is an achievable constraint by the vehicle in 2D space. Although the path generated in Section IV has continuous curvature, the curvature extrema have yet to be considered. Those piecewise paths whose curvatures exceed a specified threshold are physically unreachable. Here, a geometric path transition mechanism is established to meet these curvature upper bound constraints.
Considering the complete space of solutions, two classes of over-curved path transition are proposed: no waypoint on path and one waypoint on path. When replanning a piecewise path, it is essential to understand what kind of transition problem it presents so that it can be solved in an appropriate manner.
Figure 5 shows the two classes of path transition. The first category (shown in the rectangular boxes) is where the over-curved segment is a part of the path curve between two adjacent waypoints. Similarly, the second category (shown in the elliptical boxes) represents curve segments that pass through a waypoint.
5.1. Analytical Solutions of the Minimum Curvature Circle Transition
It has been demonstrated that a cubic curve can be used for transitions preserving
continuity and that two variables
are required to generate the expected connections [
35]. From the results of [
35], it appears that the value of parameter
m was determined by trial and error. Here, we want to determine the value of
m for given star and end point. This can be achieved using the following theorem.
Theorem 1. If the centers of the two minimum curvature circles are known, there is a unique curvature-constrained curve connecting two points, one located on each circle.
Proof. When a local frame is set up, the angle between the x-axis and the line segment between the two circle centers is (for
s-shape):
The parameters for
s-shaped and
c-shaped curves can then be obtained from (
12) and (
13), respectively.
This is derived by assigning
and
to (
12) and (
13).
Here, is equal to .
is the radius of the minimum curvature circle; is equal to ; is the angle tangent of the x-axis and the straight line connecting two circle centers; r represents the distance between the circles’ centers; and denotes the center coordinate where endpoints are located. ☐
It can be seen that a feasible transition can be figured out by solving (
m,
) from Equation (
13).
5.2. Transition Model for the No Waypoint on Path Case
Inspired by the approach taken in [
35], where curvature-bounded connections are achieved by utilizing arcs and cubic Bezier curves, we extend the basic
c and
s-shaped curves to develop a series of hybrid transitions, which include
,
,
and
shapes.
Figure 6 shows an enumeration of these shapes, where we can see that both the shape and length of the curves vary substantially between transition types. Since UAVs proceed in a predetermined direction along their trajectories, the tangent to the transition curve must be considered. Transition curves can be divided into two categories depending on whether or not the rotation orientation switches between the start and end points. To be specific, the
c,
and
shapes guarantee that the curve goes clockwise or anticlockwise, while it reverses direction for
s,
and
shapes.
To satisfy the maximum curvature condition, a minimum-curvature circle is employed to pass through the points whose curvature values exceed the threshold. A minimum curvature circle is defined as one whose curvature radius is in accordance with the settled curvature threshold. As the minimum curvature circle transition model is built in a local coordinate system, the global coordinates have to be converted to the local coordinates. We set the first point with the curvature threshold as the center of the local coordinates. The transformation matrix is constructed as follows.
The transformation matrix includes rotation and translation operations,
R and
T, respectively. Using the inverse of this matrix, the local coordinates can be derived from the global reference system:
where
denotes the global coordinates and
denotes the local coordinates.
Although the points to be connected are located on the minimum curvature circles, it can be shown that both the s and c-shape transition formulas hold in a bounded interval, which is determined by Theorem 2.
Theorem 2. The lower bound on the feasible interval is determined by setting m to one and the upper bound by the intersection of the inner or outer tangent lines and circles, respectively, for s and c-shape transitions.
Proof. We consider an
s-shape transition curve
here. Set the angle of
and
to
. In addition,
and
are parallel to the x-axis. This can be summarized as:
where
g,
h and
k are the straight-line distances between the control points of Bezier curves.
are the control points of Bezier curves. According to the results in [
34], whether or not the curvature derivative of
vanishes on [0,1] depends on the value of
Q, where:
Letting yields , while , which makes as . Meanwhile, the value of h approaches zero when the transition curve points start at the intersection of the inner tangent lines and the circle. ☐
From the above proof, we can see that and determine the boundary condition for s-shape transition.
5.3. Approach for the One Waypoint on Path Case
In addition to the approaches above, a hybrid transition mechanism has also been proposed for more complicated situations. Although the
s-shape and
c-shape models can solve curve transition problems between two points with controllable curvature extrema, this mechanism is essentially for determining the parameters of the cubic Bezier curves’ control points using curvature monotonicity conditions. Compared with the situations studied in
Section 5.2, a much more complicated application is one where one or more waypoints on the path need to be replanned. A single
s-shape or
c-shape solution could not satisfy replanning requirements because the transition curve control parameters are determined once the start and end points are given. In such cases, the curve shapes are fixed, and thus, the requirement to pass through the waypoints cannot be ensured. Therefore, changes are needed for each pair of points on the path curve. To solve this problem, a hybrid transition approach is proposed, which includes the following combined connections:
-,
-,
- and
-shaped curves. Using these, an auxiliary minimum curvature circle can be constructed to reach the specified waypoint. Afterwards, an
s-shape or
c-shape transition is employed to connect the points to this circle within the curvature threshold via piecewise arcs.
The key to finding solutions for these hybrid transitions is to estimate an appropriate position for the center of a minimum curvature circle. Results in
Section 5.2 prove that a transition is valid when the start and end control points of an
s or
c curve fall within restricted ranges. For this reason, there is a wide choice of possible curve parameters, which give rise to different curve lengths. To optimize the path, an optimal position for the center must be found.
To determine the optimal center position of the auxiliary circle, the boundary conditions should first be established. Results in
Section 5.2 show that the points of tangency on the inner tangent lines between two minimum circles are upper bounds on the end points for
s-shape transition curves. The lower bounds can be determined by setting
m to one. As an illustrative example, consider three pairs of points and their minimum curvature circles, as shown in
Figure 7. Here, Point 1 and Point 2 are the predetermined start and end points, and
is a predefined waypoint. The tangent directions at the start and end points are both counter-clockwise. Additionally, the fixed point
is required to be on the sub-path. For simplicity’s sake, the circle that passes through
is defined as an auxiliary circle as follows.
By constructing an outer tangent line to
(the minimum curvature circle passing through
) from
as shown in
Figure 8, the intersection point determines a bond on
. This is because the end point of the transition curve crosses the waypoint as the circle center moves in a counter-clockwise direction along its orbit, and thus, we want the UAV to move along an arc on the minimum curvature circle to travel across the waypoint, leading to an increase in path length. In addition, another bound on
can be obtained by drawing a line parallel to the x-axis from point
, which intersects the circle at
as shown in
Figure 8. As the circle center moves clockwise, the horizontal velocity component simultaneously reverses direction. Consequently, bounds on the circle center for an
transition are given by the blue dotted line. Auxiliary circle center bounds for other hybrid transitions can be acquired likewise.
Compared with conventional search algorithms, binary search has the advantages of low time complexity and no need for any other search region interventions. Thus, it is used to determine the position for the center of the auxiliary circle. The iterative process is summarized in Algorithm 1.
Algorithm 1 Binary searching algorithm for optimal circle center. |
Input: Lower and upper bound Output: Optimal circle center 1: Initialize the circle center (x,y); 2: Determine the starting position and the ending position ; 3: Let and be the initial and final poses of the circle center trajectory, and compute the center (,) and (,); 4: while ; 5: if then; 6: ; 7: else 8: Break; 9: end if 10: end while |
The above process consists of two phases: specification of the search region and iterative search. Utilizing the auxiliary circle center bounds determined by the previous analysis, we create an objective function that optimizes for curve length. As a result, the iteration terminates when the minimum length is obtained. Binary search is well known to have a time complexity of .
5.4. Novelty of the Proposed Transition Method
Although constructing curves with monotonic curvature using arcs and Bezier curves is quite standard in math, our method was unique as we apply the simple method in UAV path planning. The novelty is exhibited as follows: (1) on the condition that the re-planned curves had monotonic curvature, arrival of intermediate waypoints was achieved by using a minimum curvature circle; (2) -, -, - and -shaped curves were designed to connect adjacent waypoints, ensuring a UAV flied along the predefined direction; (3) the shortest replanning path was determined using the binary searching method on the basis of the auxiliary circle center’s boundary condition.