1. Introduction
Path planning consists of defining a sequence of movements from a starting point aiming to reach a desired destination while avoiding collisions with objects in the workspace [
1]. Considering the significant advances of robotics and control technologies, this research topic has been extensively studied in the literature in the context of several practical applications. It has become of particular interest to unmanned aerial vehicles (UAVs), which must rely on the accurate and safe movement for accomplishing distinct tasks [
2].
Path planning often involves significant complexity owing to constraints associated with the differential speed and acceleration [
3], the atmospheric turbulence that makes it difficult to follow a given route accurately [
4], the three-dimensional (3D) workspace, and little information about the environment considering limitations of the sensing system [
5]. One of the main aspects associated with path planning is the uncertainty with respect to the presence of unknown or unexpected obstacles in the workspace, which demands the continuous monitoring during operation. Therefore, the adaptation and/or recalculation of a given path is essential to ensure the safe operation of vehicles. In the context of global path planning, it requires the previous knowledge of the whole workspace, thus allowing the path to be planned offline, but without the possibility to perform changes in the scenario. On the other hand, online or local path planning relies on the detection of obstacles during the task on a real-time basis [
6].
Among the various path planning techniques available in the literature, artificial potential fields (APFs) can be regarded as an interesting local approach for the application developed in this work. The potential fields present a simple algorithmic structure and low computational burden, which makes it feasible for real-time applications [
7]. The generated path can maintain a safe distance from obstacles and produce smooth tracking. In addition, this strategy can be promptly applied in dynamic environments with random dimensions since its adaptive algorithm can handle uncertainties in the workspace without requiring any recalculation [
8]. However, it still presents inherent drawbacks such as loc al minima trapping, the lack of paths between closely-located objects, unreachable targets, and oscillations in the presence of obstacles or narrow passages [
9].
A plethora of algorithms have been proposed in the literature, either based on associating APF with other techniques or by modifying the characteristics of the traditional solution [
10]. For instance, in order to minimize problems of local minima and unreachable targets, an improved APF algorithm is presented in [
11], which proposes an optimization of the repulsive force orientation angle and the gravitational field function, thus allowing the robot to avoid local minima. Although the results are promising, the author reports that there is a high probability of collision with the target at the final approach instant.
A black-hole potential field was associated with a reinforcement learning algorithm to reduce the occurrence of local minima under multi-target circumstances in [
12]. The results showed that a trained agent can adapt to scenarios containing new types of obstacles quickly. However, it is necessary to improve the adaptability of the algorithm because the size of the black hole domain must be defined for different environments. Furthermore, according to the authors, collisions and congestion may occur in multi-agent systems.
In order to mitigate local minima and oscillations in trajectories, an improved APF solution is combined with fuzzy logic in [
13]. When the UAV falls into the local minimum position, one or more virtual targets are set to guide the robot out of the dead zone. The association with the fuzzy controller makes the trajectory smoother. However, simulations were performed only considering static obstacles. In environments containing many obstacles, the trajectory may also be excessively longer.
The study proposed in [
14] presents a solution for tracking a target in an environment with dynamic obstacles. The authors propose a modification on the repulsive field by taking into account the obstacle dynamics (position and speed) and their dangerousness. The algorithm was tested through simulations in a 3D environment with the presence of a single agent.
Particle swarm optimization (PSO) was combined with the APF method as in [
15]. The authors propose a particle swarm-optimized, tangent vector-based APF planning algorithm to shorten the path length and eliminate local minima. Experimental results evidenced that the proposed algorithm could effectively improve path planning efficiency. However, the analysis considered only static environments with a single agent.
The left turning potential field method and virtual target technique are proposed in [
16]. The first method forces the UAV to turn 90° to the left and escape the local minimum. The second one sets a virtual target point as an appropriate position when the robot falls into a local minimum trap. Both methods are promising but they have limitations, such as reaching the target in environments with close proximity obstacles.
Rapidly-exploring random trees and APFs are combined into a hybrid strategy presented in [
17]. Rapidly-exploring randomized trees are first used to determine a suitable path to maneuver around all obstacles in the workspace. Once a path has been determined, attractive and repulsive potential fields are implemented at all points along it and a gradient optimization algorithm is used to determine paths to reach the desired target. The authors report that further work is necessary to obtain optimal paths since the planned one may be excessively long.
The APF method is combined with rotational vectors aiming at the formation control of UAVs and obstacle avoidance in [
18]. The potential fields with rotational vectors around the obstacles adjust the direction of UAV to lead it toward its target without being trapped in local minima. The effectiveness of the algorithm was verified through simulations in the presence of static obstacles only.
An algorithm inspired by the concept of APFs and behavior-based approximation is proposed in [
19]. The objective is to allow multiple robots to navigate in formation in an optimal path and time, in addition to avoiding obstacles. The performance of this algorithm is validated in a simulation environment. From the measurements of path length and traveled time, it was observed that the proposed algorithm outperforms techniques such as A*, RRT, and genetic algorithms. However, the analysis was performed solely in the presence of static obstacles.
A hybrid path planning method is proposed in [
20] to obtain collision-free paths and improve the vehicle stability by combining the potential field with a sigmoid curve. The repulsive and attractive potential fields are redesigned by considering safety and feasibility issues. The collision avoidance and vehicle dynamics are considered to obtain the shortest path composed of sigmoid curves. The effectiveness is examined by simulations in multi-obstacle dynamic and static scenarios. However, the analysis is performed only for two-dimensional (2D) environments. In addition, the authors report that further studies are necessary to address the local minima problem and to ensure the obstacle avoidance in more complex and unknown environments.
The authors in [
21] focus on using a distributed architecture to plan the trajectories of a group of mobile robots. Each robot must be able to detect and avoid collisions with both static and dynamic obstacles present in its environment/neighborhood. A hybrid approach combines three techniques: the APF method, the neighborhood system, and the notion of priority between the robots. The problem of the intersection of robots at the same passage point is solved through the assignment of priority. However, the neighborhood detection technique reduces the influence area of each robot aiming to optimize the calculation time. Additional investigations are required to obtain optimal paths since the planned path and travel time may be excessively long.
An algorithm is introduced in [
22] for designing/controlling trajectories of multiple spacecrafts in formation while avoiding collision. The work describes a potential field for formation, which consists of structural and repulsive potentials to allow multiple agents to maintain a regular polygonal shape. Moreover, a rotational potential field in the 3D space is incorporated for collision avoidance with the obstacles. The authors report that the algorithm presents a simple formulation and low computational burden, but the results were evaluated through simulations comprising static obstacles.
In this context, this work presents a path planning algorithm applied to an aircraft swarm in a dynamic environment. Considering that the algorithm simplicity and low computational burden are of major interest in real-time practical applications, a modified APF algorithm is chosen instead of simply combining distinct approaches. Among several solutions available in the literature, it is reasonable to state that combining the rotation and repulsive fields may lead to a more efficient solution for dealing with the inherent limitations in the conventional APF method. In this sense, the main contributions of this work include:
implementation of a modified APF algorithm with a vortex field that spins over three directions aiming to avoid local minima, collisions, as well as oscillations in narrow passages and in the influence threshold associated with the obstacles;
development of a technique in which each aircraft analyzes its position in relation to the obstacles and the target, individually determining the best direction of rotation for the vortex field generated by each obstacle aiming at safe motion in the workspace. In this way, agents can adapt to scenarios with new types of obstacles on a real-time basis;
discussion of experimental tests performed with aircraft model Crazyflie 2.0 in a scenario comprising dynamic targets, as well as obstacles that may require the hierarchical cooperation among agents. From the results, it is possible to verify that the algorithm is viable to be applied in real-time experiments.
The remainder of this article is organized as follows.
Section 2 describes the modeling and control of the UAV.
Section 3 describes the modified APF approach introduced in this work.
Section 4 discusses the methodology, whereas
Section 5 presents computational and experimental tests and an in-depth discussion of the obtained results.
Section 6 discusses the main conclusions and possible future work.
2. Modeling and Control of a Quadrotor
The aircraft model Crazyflie 2.0 was adopted in this work because of its small dimensions, thus allowing the use in narrow indoor environments. Moreover, it has open code firmware and physical interfaces so that it is possible to adapt the aircraft to a wide variety of applications. It is also commercially available, making it easier for other researchers to reproduce the results, and it also allows the focus to be on the development of a robotic application without the need to build a new vehicle, which is outside the scope of this work.
Crazyflie 2.0 weighs about 27 g, with diagonally-opposed axes of 92 mm and a payload of 15 g. The power supply consists of a 3.7 V, 240 mAh lithium polymer (LiPo) battery, which provides a flight autonomy of up to five minutes [
23]. The sensing system employs an inertial measurement unit (IMU) that integrates three-axis gyroscopes, accelerometers, magnetometers model MPU-9250, and a pressure sensor model LPS25H. The aircraft also has an ultra-wideband indoor positioning system known as a loco positioning system. It operates through the exchange of high-frequency radio messages between receivers in the aircraft and anchors placed in the environment. This system is based on module DWM1000 and has an accuracy of ±0.10 m [
24].
The dynamic model of the UAV was derived using the Euler–Lagrange representation. For this purpose, one can assume that the aircraft has a rigid and symmetrical structure, with a center of mass that coincides with the origin of the coordinate system fixed to the rigid body. In addition, the propellers are rigid. The thrust and drag forces are proportional to the square of the speeds of the propellers, whose moment of inertia is negligible. Two coordinate systems were employed in the representation:
, which is inertial and fixed to the surface of the Earth;
, whose origin coincides with the center of gravity of the aircraft as shown in
Figure 1.
Vectors
and
represent the position of the center of mass and the orientation of the UAV, respectively. Additionally,
is the roll angle,
is the pitch angle, and
is the yaw angle, which were obtained using the Tait–Bryan notation. From the general Euler–Lagrange equation, it is possible to write the following equations
where
and
are the generalized forces and torques, respectively;
L is the Lagrangian, which is defined as the difference between the kinetic and potential energies;
is the vector of generalized coordinates.
According to the aforementioned premises, the Lagrangian does not contain energy terms combining the positional and angular derivatives. Therefore, the Euler–Lagrange equations can be divided into two decoupled systems comprising the translational and rotational dynamics.
In the translational system, the Lagrangian depends on the translational kinetic energy and the potential energy according to the following equation
where
m is the aircraft mass and
g is the gravitational acceleration.
Substituting Equation (2) in the Euler–Lagrange formulation (1), as well as considering the force in the inertial coordinate system, the translational dynamics can be defined according to Newton’s second law as
where
is the resulting thrust force produced by the four rotors.
The Lagrangian of the rotational system depends only on the rotational kinetic energy and can be defined as
where
acts as the inertia matrix expressed in terms of the generalized coordinates
.
Similarly, substituting (4) in (1), the angular part of the Euler–Lagrange equation assumes the following form
where
are the torques associated with the unbalanced thrust forces caused by the rotors and
are inertia moments.
It is worth mentioning that one can obtain the dynamic equations of a quadcopter following the procedure described in [
25]. Crazyflie 2.0 aircraft parameters are also available in [
26]. Furthermore, the parameterized model was used in this work to tune the controllers.
Since the quadcopter is an underactuated mechanical system, a cascade control strategy was used, in which the inner loop regulates the orientation, whereas the outer loop is responsible for the translational system as shown in
Figure 2. Each loop is divided into two subsystems responsible for regulating the zero-order states and their respective derivatives, resulting in a total of 12 controllers.
The proportional–integral–derivative (PID) controller employed in the quadcopter can be represented in terms of the following expression
where
Kp,
Ki, and
Kd are the proportional, integral, and derivative gains, respectively;
Ts is the sampling period;
ek and
ek−1 are the present and past values of the error signal, respectively;
uk is the output signal. Anti-windup limiters are associated with the integral term |
Ilim| and the output signal |
ulim|.
Crazyflie 2.0 presents a basic tuning for the controller, which can be improved to meet the specific constraints of this project. The controller was then tuned considering the integral absolute error (IAE) as an evaluation metric. The analysis was performed in a computational environment based on the parametrized model of the aircraft and further experimental validation. The obtained parameters are shown in
Table 1. The state estimation of the aircraft is performed by means of the sensory data fusion obtained from the IMU, as well as information from the local positioning system through an extended Kalman Filter [
23]. The outer loop operates at 100 Hz. In the inner loop, the angular rate and angular position controllers operate at 500 Hz and 250 Hz, respectively.
4. Methodology
The APF algorithm presented in this work was implemented in MATLAB software. For path planning purposes, a scenario involving a swarm with two aircrafts in the presence of a target and a dynamic obstacle was proposed. The scenario was arranged in the form of a challenging task for traditional path planning algorithms. In other words, a single target is defined for both aircrafts in order to assess the mutual repulsion between them and the capability of the algorithm to keep them equally distant from the target. In addition, the target trajectory defined in a ring shape was generated to remain hidden by the obstacle during a few seconds, aiming to evaluate the decisions made by each agent to avoid collisions. The reduced dimensions and short execution time of the tests aims to reproduce the procedure easily for small aircrafts with low flight autonomy in indoor environments. Technical data involving the scenario are available in
Table 3.
In order to evaluate the performance of the method proposed in this work, the algorithm is compared with the conventional APF approach, which does not include the vortex field as proposed in [
27], and with the left turning APF algorithm (LTAPF) presented in [
16].
The conventional APF algorithm does only incorporate attractive and repulsive fields. Therefore, it is not capable of overcoming issues such as local minima and oscillations in trajectories. The LTAPF method employs a vortex field that drives the agent to the left whenever it gets stuck on a local minimum point.
The comparison aims to demonstrate that the use of rotating fields combined with the possibility to determine the best spin direction of the vortex field associated with each agent leads to improved performance while also overcoming inherent problems in the traditional APF method without a significant increase in computational burden.
Computer simulations were carried out using the aforementioned path planning algorithms in the scenario described in
Table 3. The metrics for comparing the results include the presence of collisions, the final distance to the target, the total distance covered by each aircraft, and the average distance between each aircraft and the target. The presence of oscillations in the trajectories is also analyzed. The simulations do not take into account the dynamics of the quadrotor but the kinematic constraint only with respect to the translational velocity.
After analyzing the computational results, experimental tests were carried out with a real aircraft in order to evaluate the feasibility in real-time applications. The experiments used Crazyflie 2.0 quadcopters combined with the indoor positioning system.
Figure 4 shows the eight anchors of the positioning system, as well as a receiver (tag) attached to the top of the aircraft.
The experimental tests were carried out using a Python script written according to Algorithm 1. The code is responsible for allowing the radio communication with the aircrafts, enabling the path generator written in MATLAB (Algorithm 2) and for storing the measured data.
Algorithm 1 operates as follows. Initially, the variable that controls the total test time (t) and the initial positions of the aircraft are declared. After the algorithm checks the status of the quadcopters, they are sent to the starting positions. Variable t_test is initiated in line 7 while counting the time elapsed after each test. Then, the main loop is executed until the test time is reached.
Setpoints are sent at intervals of about 1000 ms, while the current aircraft positions are received at intervals of 100 ms and stored in
UAV_
position matrix. This matrix is arranged in such way that the columns represent the sequence of coordinates (
x,
y,
z) of all vehicles sequentially, whereas the rows are constantly updated with the values sent by the quadcopters.
Algorithm 1: Python Interface |
1 | Input: none |
2 | Output:UAV_position, UAV_SP |
3 | Declare:t, UAV_initial_position |
4 | Check_crazyflie () |
5 | Send_crazyflie (UAVs_initial_position) |
6 | UAV_position = Get_crazyflie_position () |
7 | Start (t_test) |
8 | While t_test <= t do |
9 | Start (t_control) |
10 | UAV_position_vec.append (UAV_position) |
11 | Time_vec.append = t_test |
12 | New_SP = Modified_vortex_APF (UAV_position (end), t_test) (presented in Algorithm 2) |
13 | Send_crazyflie (New_SP) |
14 | UAV_SP.append = New_SP |
15 | Wait (t_control => 1000 “ms”) |
16 | end While |
17 | Land_Crazyflie () |
18 | Save UAV_position, UAV_SP, Time_vec |
The MATLAB function, called in line 12, receives the instant positions of all quadrotors and time information so as to handle the virtual scenario properly. After the execution, the new setpoints are sent to the vehicles (line 13) and stored on UAV_SP matrix (line 14), which has the same structure as UAV_position.
Once the test exceeds the defined value t, the script exits the “while” loop, calls the high-level function to land the quadcopters safely (line 17), and stores the data in txt files so they become accessible for latter analysis and plotting (line 18).
The modified APF method proposed in this work is describe in Algorithm 2. It receives the instant time (t_test) and vehicle positions (UAV_position) in order to calculate the new setpoints for the quadrotors. First, based on the scenario configuration, the target and initial positions of obstacles are declared, as well as their respective speeds. In addition, the coefficient gains for the attractive (k_a), repulsive (k_r), and vortex (k_v) fields and the velocity constraint for the Crazyflie aircrafts (max_vel) are also declared (line 3). This assignment occurs only once and is not callable by the Python script every cycle.
The positions of the target and obstacle are updated. Once UAV_position vector contains the coordinates (x, y, z) of each aircraft, the amount of Crazyflie aircrafts is determined as shown in line 7. Then, a “for” loop is executed for calculating the setpoints for each j-th vehicle. A vector containing the indexes corresponding to the j-th aircraft is then created in line 9, considering that the first index of a vector is 1.
The script creates a cell array namely Obs_expand, which comprises the information of the positions of the obstacle and all the other vehicles “not(j)” (line 10). After that, the spin directions for the obstacle and all the remaining aircrafts are determined, resulting in the later calculation of the attractive, repulsive, and vortex fields.
The workspace resultant field for the
j-th quadrotor is calculated from the weighted sum of the aforementioned fields (line 15) associated with their respective gains. Thus, the new setpoint is found using the steepest descent method (line 16). Before this procedure is repeated for the next agent, the setpoints are properly stored in
UAV_SP vector. Once the new setpoints are determined for all vehicles, the routine returns
UAV_SP.
Algorithm 2: Modified APF |
1 | Input: UAVs_position, t_test |
2 | Output: UAV_SP |
3 | Declare Target, target_speed, Obstacle, obstacle_speed, k_a, k_r, k_v, max_vel |
5 | Target_pos = update (Target, target_speed, t_test) |
6 | Obstacle_pos = update (Obstacle, obstacle_speed, t_test) |
7 | n_UAV = length (UAV_position)/3 |
8 | for j = 1: n_UAV do |
9 | j_index = [1 + 3 ∗ (j − 1) 3 ∗ j] |
10 | Obs_expand = (Obstacle_pos, UAV_position (not (j_index))) |
11 | spin_dir = Vortex_field_spin_direction (Target_pos, Obs_expand, UAV_position (j_index)) |
12 | Att_field = Attractive_field (Target_pos) |
13 | Rep_field = Repulsive_field (Obs_expand) |
14 | Vor_field = Vortex_field (Obs_expand) |
15 | WS_field = k_a ∗ Att_field + k_r ∗ Rep_field + k_v ∗ Vor_field |
16 | new_SP = steepest_descent (WS_field, max_vel) |
17 | UAV_SP (j_index) = New_SP |
18 | end for |
19 | Return: UAV_SP |
The workspace was sampled at a resolution of 50 points per meter. This value was determined during experimental tests and represents a good tradeoff between accuracy and computational burden, comprising a maximum system error of ±0.0144 m. The trajectories are calculated considering that each aircraft is a material point allocated at its center of mass, while the dimensions of the obstacles are expanded by a safety factor equals to 0.2 m.
The safety factor was chosen as the sum of the radius of the aircraft, that is, approximately 0.0661 m and the measurement uncertainty of the local positioning system, provided by the manufacturer, which is equal to 0.1 m, added by a 20% security margin.
The simulations and experimental tests were carried out on a computer with the following configurations: Ubuntu 20.04 LTS operating system, Intel Core I7-4790 3.60 GHz processor, 16 GB of RAM memory, and GTX960 video graphic card.