1 Introduction

Recent advancements in electric propulsion systems have led to the development of various types of vertical take-off and landing (VTOL) unmanned aerial vehicles (UAVs) such as multi-copters, tilt-rotors, quad-tilt rotors, tail sitters, electric turbo jets and ducted fan UAVs. According to the federal aviation administration (FAA), the number of UAV operators is expected to reach 770,000, and about 442,000 drones will be operating by 2021 [1]. VTOL UAVs including drones are usually operated at low altitude, and collision accidents caused by ground obstacles such as trees and buildings are becoming important issues. Recently, various obstacle collision avoidance algorithms have been studied in the field of robotics due to the development of smaller and lighter laser scanners and graphics processing units (GPUs) parallel processing technology.

The collision avoidance problem can be classified into path planning, which generates paths based on geometry, and trajectory or motion planning which considers the dynamic constraints of the system [2]. Path planning is an algorithm that finds the optimal trajectory, but it takes a long time to find the optimal solution in general. Therefore, a real-time motion-planning algorithm is well suited for collision avoidance in robotics. There are three approaches in motion planning. The first method is the potential-field based algorithm in which the destination has an attraction force field that draws the vehicle, and the obstacle has a repulsive force field. These force fields enable the vehicle to reach the target with obstacle avoidance. Virtual force field (VFF) and vector field histogram (VFH) are considered as potential-field based algorithms. The second method is to sample and combine collision avoidable points based on a random sampling technique. Reachability graph, probabilistic roadmaps, and RRT* (Rapidly exploring random tree) are typical examples [3, 4]. Scherer et al. [5,6,7] verified terrain obstacle avoidance landing techniques through flight tests with the H-6U helicopter equipped with a laser scanner in TALOS (Tactical autonomous aerial logistics system) program. The third method is an algorithm that directly uses the dynamic characteristics of a vehicle. Typical examples are model predictive control (MPC), dynamic window approach (DWA), nearness diagram (ND), and curvature velocity method (CVM). Shim et al. [8] applied the nonlinear model predictive control (NMPC) to a Yamaha agricultural unmanned helicopter to verify collision avoidance between a terrain and the helicopter through flight tests. Kamel et al. [9] also applied NMPC to the collision avoidance of a quadcopter for indoor flight tests.

DWA is one of the most widely used collision avoidance algorithms as a local planner in the field of robots and has recently been used for multi-copters. Vista IV et al. [17] applied convergent DWA with an exponential function on multi-copter collision avoidance and Berger et al. [10] combined 2-pass A* and a DWA-based-octomap structure for a quad-copter.

In DWA, the dynamic model and cost function formula depend on the dynamic characteristics of the vehicle. A holonomic vehicle is a system that can move in any direction, such as a mobile robot equipped with a Mecanum wheel or omni-directional wheel. A non-holonomic vehicle is a system that can move only in a specific direction for a moment, and this is common in mobile robots and automobiles. In mathematics, it is called ‘holonomic’ when the dynamic equation can be expressed as a self-explanatory function using the position variables; i.e., the degree of freedom that can be controlled is equal to the total degree of freedom. On the other hand, it is called ‘non-holonomic’ when the velocity variables are included as well as the position variable; i.e., the degree of freedom that can be controlled is less than the total degree of freedom. In the case of multi-copters and small helicopters, the holonomic DWA algorithm of mobile robots can be easily applied because they can fly in all directions directly. However, they are not appropriate for tilt-rotor UAVs or large-scale helicopters. Manned scale helicopter’s (e.g., MD500, UH-60, AH-64, etc.) maneuver is similar to multi-copters at low speeds, but they fly like a fixed-wing aircraft at high speeds with limited turn rate and lateral speed. Tiltrotor UAVs also have a transition corridor, in which the control architecture and maneuver limits significantly vary [11, 12]. Therefore, a collision avoidance algorithm that takes into account the dynamics of the entire flight envelope is required to avoid collisions with obstacles for VTOL UAVs.

In this paper, a hybrid DWA that extends the search space of DWA from 2D to 3D to reflect both the holonomic dynamics in low-speed regions and non-holonomic dynamics in high-speed regions is proposed as a method for collision avoidance of unmanned helicopters or tilt-rotor UAVs. The remainder of this paper is organized as follows. Sect. 2 describes the dynamics of a helicopter and its control structure. Sect. 3 reviews the dynamic window approach, which is the foundation of the collision avoidance algorithm proposed in this paper. Sect. 4 extends the search space of DWA to three dimensions as a hybrid DWA for VTOL UAVs. Sect. 5 presents the simulation results of DWA and hybrid DWA in various obstacle environments. Finally, the conclusions are presented in Sect. 6.

2 Dynamics of a VTOL UAV

2.1 Control Response Type of a Rotorcraft

Control response type is the control method of a rotorcraft using a fly-by-wire system and includes rate command, attitude command/attitude hold (ACAH), position hold (PH), and transitional rate control (TRC) mode which follows the forward/lateral speed command [13]. Figure 1 shows the control response type of the AH-64 helicopter automatic flight control system (AFCS). In the hover and low speed condition, the control stick input is used as the TRC or ACAH control response type, while the stick input is used as the speed command or the bank angle command at high-speed [14]. The pedal command is converted directly to the yaw rate command in the hover or low speed condition, and it makes a quick turn maneuver. However, at high speed, similar to a fixed wing aircraft, the bank is used for the heading control and waypoint guidance instead of the yaw rate command [15].

Fig. 1
figure 1

Control response type of a helicopter AFCS

2.2 Lateral Dynamic Equation of a VTOL UAV

The dynamic model of a VTOL UAV in normal flight can be expressed as the perturbed equations of motion in a state-space form matrix notation [16]. The lateral dynamic model consists of a side force, rolling and yawing moment terms. In the case of hover flight, the dynamic equation can be expressed as Eq. (1) because the roll, pitch attitude and forward velocity are close to zero.

$$ \left[ {\begin{array}{*{20}c} {\dot{v}_{y} } \\ {\dot{p}} \\ {\dot{\phi }} \\ {\dot{r}} \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {Y_{{v_{y} }} } & 0 & g & 0 \\ {L_{{v_{y} }}^{'} } & {L_{p}^{'} } & 0 & {L_{r}^{'} } \\ 0 & 1 & 0 & 0 \\ {N_{{v_{y} }}^{'} } & {N_{p}^{'} } & 0 & {N_{r}^{'} } \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} {v_{y} } \\ p \\ \phi \\ r \\ \end{array} } \right] + \left[ {\begin{array}{*{20}c} {Y_{\delta } } \\ {L_{\delta }^{'} } \\ 0 \\ {N_{\delta }^{'} } \\ \end{array} } \right]\delta $$
(1)

Here, \( L^{'} \) and \( N^{'} \) are the effect of the cross product of inertia.

$$ L' = \frac{{L + \left( {I_{xz} /I_{xx} } \right)N}}{{1 - \left( {I_{xz}^{2} /I_{xx} I_{zz} } \right)}},\,\,N' = \frac{{N + \left( {I_{xz} /I_{zz} } \right)L}}{{1 - \left( {I_{xz}^{2} /I_{xx} I_{zz} } \right)}} $$
(2)

On the other hand, the side slip angle is dominantly applied to the lateral force equation rather than the lateral speed as mentioned in the control type in the case of forward flight in advance and can be expressed as Eq. (3).

$$ \left[ {\begin{array}{*{20}c} {\dot{\beta }} \\ \begin{aligned} {\dot{p}} \hfill \\ {\dot{\phi }} \hfill \\ \end{aligned} \\ {\dot{r}} \\ \end{array} } \right] = \left[ {\begin{array}{*{20}c} {Y_{\beta } /v_{x} } & {Y_{p} /v_{x} } & {g\cos \theta_{0} /v_{x} } & { - 1 + Y_{r} /v_{x} } \\ {L_{\beta }^{'} } & {L_{p}^{'} } & 0 & {L_{r}^{'} } \\ 0 & 1 & 0 & 0 \\ {N_{\beta }^{'} } & {N_{p}^{'} } & 0 & {N_{r}^{'} } \\ \end{array} } \right]\left[ {\begin{array}{*{20}c} \beta \\ \begin{aligned} p \hfill \\ \phi \hfill \\ \end{aligned} \\ r \\ \end{array} } \right] + \left[ {\begin{array}{*{20}c} {Y_{\delta } /v_{x} } \\ {L_{\delta }^{'} } \\ 0 \\ {N_{\delta }^{'} } \\ \end{array} } \right]\delta $$
(3)

From the relationship between the roll rate (\( p \)), roll angle (\( \phi \)), lateral speed (\( v_{y} \)) and the side slip (\( \beta \)) of Eqs. (1) and (3), the lateral speed in Eq. (1) is directly affected by the roll angle in the hover or low-speed condition. TRC mode is a basic example in which the pilot stick command is applied to the lateral speed command at low speed. However, in Eq. (3), the roll angle does not directly affect the side slip angle, but the roll rate and yaw rate influence the side slip angle. This is related to a coordinated turn at high-speed flight. It can be seen that the yaw rate is not independent during forward flight and is related to the side slip angle, i.e., the yaw rate not only changes heading but also causes a slip/skid maneuver and affects lateral acceleration and lateral speed.

2.3 Guidance and Control of a VTOL UAV

The control law structure of a helicopter is briefly shown in Fig. 2 [17]. The longitudinal axis consists of a speed control loop with a pitch controller as the inner loop, and the speed command (\( v_{{x{\text{TRC}}}} \) or \( v_{\text{knob}} \)) or the pitch command (\( \theta_{\text{ACAH}} \)) is used contingent on the control mode. The longitudinal axis controller uses the same structure in the entire speed range, while the lateral axis controller uses the lateral speed command (\( v_{{y{\text{TRC}}}} \)) in the hover or low speed condition but uses the roll command at high speed. In addition, the heading command is directly transmitted to the yaw rate controller at low speed, but it is converted as the roll command at high speed; in a real system, it is designed with gain scheduling based on the speed or turn coordination note logic. Therefore, the hover and low speed dynamics are considered as holonomic because the number of the control inputs is three as the forward speed (\( v_{x} \)), lateral speed (\( v_{y} \)), and turn rate (\( \dot{\psi } \)) and the control variable is two as the north and east position. On the other hand, a system regarded as a non-holonomic vehicle has two control inputs consisting of the forward speed (\( v_{x} \)) and the turn rate (\( \dot{\psi } \)) in the case of high-speed (\( v_{y} \approx 0 \)).

Fig. 2
figure 2

Architecture of CLAW for a VTOL UAV

3 Dynamic Window Approach

DWA was first proposed by Fox et al. [18] as an algorithm that provides an optimal solution by considering the vehicle conditions and dynamics limits. It defines a dynamic window within the maximum translational acceleration and turn acceleration of a vehicle based on the current states and predicts the states for a certain period of time. Then, collisional obstacles are mapped on the velocity vector instead of the position map. After that, it calculates the direction to the target point, the collision distance with an obstacle, and the maximum achievable speed as a cost function and selects commands for which the cost becomes maximum at every step. DWA is useful when considering mechanical and dynamic constraints because it can avoid obstacles by predicting the path before a collision; moreover, the algorithm is applicable to environments with real-time changes in surrounding obstacles [19]. The biggest advantage of DWA is its reduction in calculation time by removing non-reachable areas which is achieved by taking into account the limitations of the vehicle and generating the optimal commands by calculating all of the windows. However, the result sometimes falls into the local minima depending on the relationship between obstacles and the target position.

Brock and Khatib [20] proposed the global-DWA using the global path planner such as A* instead of the heading of the objective function to solve this local minimum problem. Additionally, Ogren and Leonard [21] introduced the concept of receding horizon control to prove the convergence of DWA using the control lyapunov function (CLF). Berti et al. [22] also proposed a cost function that included the lyapunov stability criteria and proposed improved DWA(I-DWA).

The dynamic window of a non-holonomic DWA is shown in Fig. 3 (left). The x-axis is the angular velocity of the vehicle; the y-axis is the forward velocity, and range of axes are determined by the maximum velocity and angular velocity. Based on the vehicle’s current states, collisional obstacles are represented in the velocity vector. The dynamic window of a holonomic vehicle is similar to the non-holonomic, but the x-axis represents the lateral velocity instead of the angular velocity.

Fig. 3
figure 3

Search space of the conventional DWA

4 Hybrid DWA for a VTOL UAV

Unlike mobile robots, a VTOL UAV is capable of both holonomic and non-holonomic maneuvers depending on the forward flight speed. Figure 4 shows the difference in collision avoidance maneuvering between the holonomic case and the non-holonomic case in front of obstacles. In the holonomic region, the lateral speed command is directly generated to avoid collision because the heading is maintained. The avoidance speed is slow due to the characteristics of the VTOL UAV (see Fig. 1). However, because the flight heading is maintained, it can accelerate immediately after passing the obstacle. On the other hand, in the non-holonomic maneuver (high speed), the obstacle is avoided with the maximum turn rate; afterwards, it turns back to the previous heading to the target. This avoidance maneuver is very fast, but an additional heading turn is required to the target point. Therefore, for the optimum avoidance maneuver, it is necessary to generate an optimal command considering the relationship between the current flight state, obstacle and target point considering both maneuvers rather than generating commands separately.

Fig. 4
figure 4

Collision avoidance depending on maneuvering types

When the collision avoidance maneuver is applied to DWA as shown in Fig. 5, a candidate for the velocity vector command that can be generated in a dynamic window is a combination of a low-speed holonomic velocity vector and a high-speed non-holonomic velocity vector. In this paper, we propose a hybrid DWA that considers holonomic and non-holonomic dynamics while considering aircraft turn dynamics by extending the existing DWA.

Fig. 5
figure 5

Velocity vector candidate of the hybrid DWA

4.1 Search Space for the Hybrid DWA

The hybrid DWA is an algorithm that computes the optimal solution by expanding the existing two-dimensional velocity vector coordinate system to three dimensions to calculate both the holonomic and non-holonomic dynamics. Figure 6 shows the search space of the algorithm. In the figure, the x-axis is the turn rate; the y-axis is the forward speed, and the z-axis is the lateral speed. Similar to the existing DWA, it maps the obstacle collisions to the velocity-based search space by calculating the expected trajectory of the model for the prediction time in the present state.

Fig. 6
figure 6

Search space of the hybrid DWA

The velocity space of the hybrid DWA includes the forward speed, lateral speed and the heading rate shown in Eq. (4).

$$ V_{\text{s}} = \left\{ {\begin{array}{*{20}l} {\left( {v_{x} ,v_{y} ,\omega } \right)| \cdots } \hfill \\ {v_{x} \in \left[ {v_{x\hbox{min} } ,v_{x\hbox{max} } } \right]\; \wedge } \hfill \\ {v_{y} \in \left[ {v_{y\hbox{min} } ,v_{y\hbox{max} } } \right]\; \wedge } \hfill \\ {\omega \le \left[ {\omega_{\hbox{min} } ,\omega_{\hbox{max} } } \right]} \hfill \\ \end{array} } \right\} $$
(4)

For collision avoidance, the algorithm should generate a command that does not collide with the obstacle within the velocity space, and the deceleration capability of the vehicle must be considered. Admissible velocity space means the maximum velocity space that can be stopped or avoided without encountering the closest obstacle in the current vehicle condition, and it can be defined as follows.

$$ V_{\text{a}} = \left\{ {\begin{array}{*{20}l} {\left( {v_{x} ,v_{y} ,\omega } \right)| \cdots } \hfill \\ {v_{x} \le \sqrt {2{\kern 1pt} \cdot{\kern 1pt} d_{\hbox{min} } \left( {v_{x} ,v_{y} ,\omega } \right){\kern 1pt} \cdot{\kern 1pt} a_{x\hbox{max} } } \wedge } \hfill \\ {v_{y} \le \sqrt {2{\kern 1pt} \cdot{\kern 1pt} d_{\hbox{min} } \left( {v_{x} ,v_{y} ,\omega } \right){\kern 1pt} \cdot{\kern 1pt} a_{y\hbox{max} } } \wedge } \hfill \\ {\omega \le \sqrt {2{\kern 1pt} \cdot{\kern 1pt} d_{\hbox{min} } \left( {v_{x} ,v_{y} ,\omega } \right){\kern 1pt} \cdot{\kern 1pt} \dot{\omega }_{\hbox{max} } } } \hfill \\ \end{array} } \right\} $$
(5)

Here, \( {\mathbf{V}}_{a} \) is the speed set (\( v_{x} ,v_{y} ,\omega \)) in which the UAV does not hit the obstacle, and \( d_{\hbox{min} } \) is the distance from the nearest obstacles. \( a_{x\hbox{max} } ,a_{y\hbox{max} } ,\dot{\omega }_{\hbox{max} } \) are the maximum acceleration and the angular acceleration, which are usually determined by the structural load limits and performance of the aircraft. All vehicles have a limited acceleration/deceleration performance that can be defined as a dynamic window, in which the acceleration and angular acceleration commands are applied for the prediction time \( \Delta T \) in the current state. The dynamic window can display the movable area based on the current states, and the space outside the dynamic window can be excluded from the calculation because the vehicle cannot reach it during the prediction time \( \Delta T \).

$$ V_{\text{d}} = \left\{ {\begin{array}{*{20}l} {\left( {v_{x} ,v_{y} ,\omega } \right)| \cdots } \hfill \\ {v_{x} \in \left[ {v_{x0} - a_{x\hbox{max} } \Delta T,{\kern 1pt} v_{x0} + a_{x\hbox{max} } \Delta T} \right] \wedge } \hfill \\ {v_{y} \in \left[ {v_{y0} - a_{y\hbox{max} } \Delta T,{\kern 1pt} v_{y0} + a_{y\hbox{max} } \Delta T} \right] \wedge } \hfill \\ {\omega \in \left[ {\omega_{0} - \dot{\omega }_{\hbox{max} } \Delta T,{\kern 1pt} \omega_{0} + \dot{\omega }_{\hbox{max} } \Delta T} \right]} \hfill \\ \end{array} } \right\} $$
(6)

The final search space calculated by DWA is a space that includes both a velocity space representing the maximum velocity and angular velocity and an admissible space representing an obstacle, and a dynamic window which considers the maneuvering performance of the vehicle.

$$ {\mathbf{V}}_{\text{r}} = {\mathbf{V}}_{\text{s}} \cap {\mathbf{V}}_{\text{a}} \cap {\mathbf{V}}_{\text{d}} $$
(7)

4.2 Objective Function for the Hybrid DWA

The objective function maps all the velocities in the search space (\( {\mathbf{V}}_{\text{r}} \)) to values between 0 and 1, finds the predictable position \( {\mathbf{P}}_{\text{n}} \), and computes an object function \( J \) as follows:

$$ J = \gamma_{\psi } J_{\psi } + \gamma_{\text{v}} J_{\text{v}} + \gamma_{\text{d}} J_{\text{d}} $$
(8)

where \( J_{\psi } ,J_{\text{v}} ,J_{\text{d}} \) are the cost functions indicating the heading, velocity, and distance to the obstacle, and \( \gamma_{\psi } ,\gamma_{\text{v}} ,\gamma_{\text{d}} \) are the weights of the functions. The heading function \( J_{\psi } \) represents the relative heading from the predictable position \( {\mathbf{P}}_{n} \) to the target position \( {\mathbf{P}}_{t} \) shown in Fig. 7. If \( \psi_{tn} \) is 0, i.e., the UAV is aligned with the direction of the target point, the heading function outputs the maximum value of 1. If \( \psi_{tn} \) is \( - \pi ,\,\pi \), i.e., if the heading of the UAV is opposite to the target point, the heading function outputs the minimum value of 0.

Fig. 7
figure 7

Heading candidates of DWA

$$ J_{\psi } \left( {{\mathbf{P}},{\mathbf{V}}} \right) = \left\{ {\begin{array}{*{20}l} {1 - \frac{{\left| {\psi_{tn} - \psi } \right|}}{\pi },} \hfill & \quad{{\text{if}}\;{\kern 1pt} 0 \le \left| {\psi_{tn} - \psi } \right| < \pi } \hfill \\ {\frac{{\left| {\psi_{tn} - \psi } \right|}}{\pi } - 1,} \hfill & \quad{{\text{if}}\;{\kern 1pt} \pi \le \left| {\psi_{tn} - \psi } \right| < 2\pi } \hfill \\ \end{array} } \right. $$
(9)

Here, \( {\mathbf{P}} = \left( {x,y} \right) \in \Re^{2} \) is a position vector; \( {\mathbf{V}} = \left( {v_{x} ,v_{y} ,\omega } \right) \in {\mathbf{V}}_{\text{r}} \) is a velocity vector.

The velocity function \( J_{v} \) selects the maximum speed command to reach the target point quickly under the same turning condition and converges to 0 when it approaches the destination. Here, \( d_{\text{t}} = \left| {{\mathbf{P}}_{uav} - {\mathbf{P}}_{\text{t}} } \right| \) is the Euclidean distance to the target position, and \( R_{\text{t}} \) is the radius that determines the arrival of the target point.

$$ J_{\text{v}} \left( v \right) = \left\{ {\begin{array}{*{20}l} {\frac{\left| v \right|}{{v_{\text{max} } }},} \hfill & \quad{{\text{if}}\;d_{\text{t}} > R_{\text{t}} } \hfill \\ {1 - \frac{\left| v \right|}{{v_{\text{max} } }},} \hfill & \quad{{\text{if}}\;d_{\text{t}} \le R_{\text{t}} } \hfill \\ \end{array} } \right. $$
(10)

The distance function \( J_{\text{d}} \) measures the proximity to the nearest obstacle at a given speed, outputs the maximum value when the obstacle is out of bounds, \( R_{\hbox{max} } \), and outputs a value in inverse proportion to the obstacle distance in the case when approaching the obstacle. \( R_{\hbox{max} } \) should be larger than the radius of obstacle \( R_{\text{obs}} \).

$$ J_{\text{d}} \left( {P,V} \right) = \left\{ {\begin{array}{*{20}l} {\frac{{d_{i} }}{{R_{\text{max} } - R_{\text{obs}} }},} \hfill & \quad{{\text{if}}\;d_{i} \le R_{\text{max} } } \hfill \\ {1,} \hfill &\quad {{\text{if}}\;d_{i} > R_{\text{max} } } \hfill \\ \end{array} } \right. $$
(11)

Here, \( d_{i} \) is the distance between the position of the UAV at which travels for \( \Delta T \) and the nearest obstacle.

4.3 Consideration of Forward Flight Constraints

In the conventional DWA algorithm, the resulting search space is calculated for all the grid values. However, when the helicopter flies at high-speed, additional non-reachable areas exist due to the limitations of the turn dynamics. Equation (12) shows the equation of the coordinated turn.

$$ \tan \phi = \frac{{v_{x}^{2} }}{gR} $$
(12)

where \( \phi \) is the roll angle; \( v_{x} \) is the forward flight speed; \( g \) is the gravitational acceleration, and \( R \) is the turn radius. Applying the kinematic equation (\( v_{x} = R \cdot \dot{\psi } \)) of the circular motion, the rate of turn in the navigation frame can be summarized by Eq. (13) depending on the speed as follows:

$$ \dot{\psi } = \left\{ {\begin{array}{*{20}l} { - \dot{\psi }_{\hbox{max} } < \dot{\psi } < \dot{\psi }_{\hbox{max} } ,} \hfill & \quad{{\text{if}}\;{\kern 1pt} v_{x} \le v_{\text{c}} } \hfill \\ { - \frac{g}{{v_{x\hbox{max} } }}\tan \phi_{\hbox{max} } < \dot{\psi } < \frac{g}{{v_{x\hbox{max} } }}\tan \phi_{\hbox{max} } ,} \hfill &\quad {{\text{if}}\;{\kern 1pt} v_{x} > v_{\text{c}} } \hfill \\ \end{array} } \right. $$
(13)

where \( v_{\text{c}} \) is the transition speed from low speed to high speed shown in Fig. 1, which is determined during the design of the autopilot, but mostly determined by a value between 30 and 45 knots due to the dynamic pressure characteristics of the air data system (ADS). \( v_{x\hbox{max} } \) is the maximum forward speed, and \( \phi_{\hbox{max} } \) is the maximum bank angle used in the lateral axis controller. Figure 8 shows the search window which considers the turn dynamics with a maximum bank angle of 20°. In the case of handling quality of a modern helicopter, the hover turn rate is at least 16°/s while the maximum turn rate drops to about 4°/s when the bank angle is limited to 20° at a speed of 60 m/s [13].

Fig. 8
figure 8

Dynamic window constraints of a high-speed turn maneuvering

5 Simulation Results

5.1 2D Dynamic Window and Evaluation

First, we simulated the non-holonomic DWA to understand the paths and dynamic window. The candidate path calculated by DWA in the obstacle map is shown in Fig. 9 (left); the vehicle is located in the middle position (0, 50), and the target point is located in the upper right (30, 90) and represents the candidate route predicted for 10 s based on the current heading and speed. Figure 9 (right) shows the search window at this time. The center left circle is the state of the current vehicle (\( v_{x} \) = 6 m/s; \( \omega \) = 10°/s); the obstacles that may collide with each grid command are indicated by the small circles. The command calculated from the final cost function is indicated by an arrow. At this point, if the current state is maintained, a collision with the obstacle occurs. To prevent the collision with the obstacle, the turn rate should be reduced to 0, and the deceleration command should be selected.

Fig. 9
figure 9

Candidate trajectories of the non-holonomic vehicle and 2D dynamic window

Figure 10 shows the respective cost functions for the command grid under a same situation. The heading evaluation function has the largest value at the left turn command because the target point is on the left of the current heading reference. The distance function has the largest value in the case of straight flight (turn rate = 0) due to side obstacles. Moreover, the velocity function has a higher evaluation value as the velocity increases. A final cost function that combines the three cost functions and the weighting factor selects the collision free path to the target.

Fig. 10
figure 10

Evaluation map of the 2D search window

5.2 DWA with Coordinated Turn Constraints

An aircraft has a characteristic for which the maximum turn rate is limited depending on the speed as mentioned in Sect. 4.3. Figure 11 shows the candidate paths without and with flight dynamic constraints. In both cases, it seems that they created a collision-free path; however, the non-holonomic DWA generates a turn rate command that cannot be achieved in the real world. On the other hand, when turn dynamic constraints are considered, it can be seen that a maximum high-speed turn rate command is generated as shown in Fig. 12.

Fig. 11
figure 11

Selected trajectory considering turn constraints

Fig. 12
figure 12

Comparison of the evaluation map

5.3 Comparison of the DWA and Hybrid DWA

To compare the performance and characteristics of the hybrid DWA, simulation results were compared for cases in which obstacles are aligned; obstacles surround a narrow path, and obstacles are concentrated near the target point. Table 1 shows the performance parameters of the UAV used in the simulation. Table 2 shows the calculation grid spacing, weights of the cost function, and the prediction time of the DWA algorithm.

Table 1 Performance parameters of the vehicle
Table 2 Parameters of DWA

To understand the behavior of collision avoidance, simulations results with simple aligned obstacles allocated in the center of the obstacle map are shown in Fig. 13. In the first case, the holonomic DWA reaches the target with a constant speed command without changing the heading. However, the lateral speed of the VTOL is very low because of the characteristics of the dynamics as mentioned before. On the other hand, the non-holonomic DWA changes the heading and moves toward the target point with a smoother path. This is because the area to be computed at high-speed is larger and thus creates an avoidance command before approaching the obstacle. The hybrid DWA generates a trajectory similar to the non-holonomic DWA in the mid-term, but the path changes sharply near obstacles without reducing the speed. This is because the cost function of the lateral velocity command increases relatively in the low-speed area, and the holonomic maneuver is possible.

Fig. 13
figure 13

Collision avoidance with simple obstacles

A typical disadvantage of DWA is that it is unable to pass through a narrow passage with obstacles. Figure 14 show the simulation results of a path through a narrow passage where the obstacles are located on both sides which is similar to the obstacle map used by Zhang [23]. The holonomic DWA travels with lateral speed and arrives at the target point, and the velocity is very slow due to the dynamic constraints of the VTOL (61.6 s).

Fig. 14
figure 14

Trajectory in the obstacle map with a narrow route

On the other hand, the non-holonomic DWA arrives relatively quickly to the target point through a left turn after the initial acceleration and then a right turn again with a S-shaped path because of the large heading variation (42.4 s). However, the hybrid DWA accelerates, and the heading turns at the same time reaching the target point with the fastest time (38.4 s).

DWA is a local planner and has the disadvantage of falling into the local minima depending on the heading of the obstacle, the target point, and the current vehicle [24]. In particular, when the target point and the obstacle are located in a straight line on the path, the vehicle cannot move because there is a conflict between the obstacle cost function and the heading cost function.

Figure 15 shows a non-holonomic DWA simulation result when obstacles are arranged perpendicular to the path near the target point in a grid-shaped obstacle map. In this case, the vehicle stopped with the speed command being 0 in front of the obstacle, i.e., a global planner is required to generate a new target point to overcome this problem. The trajectory of the hybrid DWA is shown in Fig. 16; despite the frontal obstacle, the vehicle avoids obstacles by the low-speed holonomic maneuver with a fixed heading near the obstacle due to the lateral speed command. After avoiding the obstacle, it reaches the target point straight ahead. This maneuver is possible because the two-dimensional DWA falls into the local minima only considering the forward speed and the heading, whereas the hybrid DWA simultaneously calculates the forward speed, heading, and lateral velocity in three dimensions, and there is a high probability of escape with new command sets near the local minima.

Fig. 15
figure 15

Trajectory of the conventional DWA in front of obstacles

Fig. 16
figure 16

Trajectory of the hybrid DWA in front of obstacles

Candidate trajectories and a selected trajectory of this situation are shown in Fig. 17. The straight path was selected near the obstacles in the non-holonomic DWA. From search space and evaluation map shown in Fig. 18a and Fig. 19, respectively, the speed reduction command is selected because of the front obstacles. However, for the trajectory of the hybrid DWA in the three-dimensional search space, the lateral speed command and left turn command are selected simultaneously from the search space shown in Fig. 18b.

Fig. 17
figure 17

Selected trajectory near the local minima

Fig. 18
figure 18

Search space of DWA near the local minima

Fig. 19
figure 19

Evaluation map of the non-holonomic DWA near the local minima

In the two-dimensional search space, the cost function distribution appears only as one point near the zero speed, whereas in the three-dimensional search space, the high evaluation value (bright color) is distributed by various command combinations including the lateral velocity (Fig. 20).

Fig. 20
figure 20

Evaluation map of the hybrid DWA near the local minima

6 Conclusion

In this paper, we propose a hybrid DWA which includes holonomic and non-holonomic maneuvers for obstacle collision avoidance of a VTOL UAV. The holonomic DWA can be applied only in a limited flight envelope including hovering and low-speed flight. The non-holonomic DWA generates a fast and smooth trajectory, but the turn rate changes depending on the forward speed. The proposed hybrid DWA complements the non-holonomic DWA and the holonomic DWA features for VTOL UAVs by extending 2D dynamic windows to 3D and adding dynamic constraints to select reachable commands only.

Collision avoidance simulations in various obstacle environments shows that the proposed algorithm generates smooth and fast trajectory in a collision-free space but generates side-step flight commands near the obstacles. In the case of the existing 2D DWA, the command value selected in the evaluation map falls into the local minima. As the evaluation map expands to three dimensions, the probability of escaping the local minima increases as observed for the saddle point of the multi-dimensional space problem. This feature enables the UAV to reach the target point while slowly avoiding the obstacle by conducting holonomic maneuvers without stopping when encounters an obstacle near the target point.

However, the hybrid DWA is still a local planner, and it is difficult to generate the optimum path and reach the target point if the vehicle needs to avoid complicated obstacles or fly along a long passage blocked in the direction of the target point. Future studies need to investigate real-time algorithm tailor-made for collision avoidance of VTOL UAVs that combine a global planner such as A* and a hybrid DWA similar to the global DWA.