1 Introduction

In the last years, we have seen an emergence of the use of Unmanned Aerial Vehicles (UAV) with a variety of structures and shapes. Their extensive use has induced the rapid growth of related research areas, both in military and in civil fields, such as, security and surveillance (Ma’sum et al. 2013), delivery (Thiels et al. 2015), search and rescues (Doherty and Rudol 2007), and fire fighting (Casbeer et al. 2005). The use of UAVs is constantly increasing, especially in urban areas (Mohammed et al. 2014). This is why the UAV should be first safely and timely designated in accordance with the target field, what is commonly known as path planning problem.

Path planning is the key element to provide autonomy to UAVs in the execution of their mission, by determining a collision-free pathway between a UAV’s current position and its destination, while satisfying some optimality criterion (Goerzen et al. 2010). Path planning has been widely studied and a large number of methods have been developed in last decades. However, most of them are not efficient in real world applications because of the dynamic, uncertain and changing nature of such environments. Mobile robots motion path planning problem can be divided into two groups: Optimized Classic Approaches, and Evolutionary and Hybrid Approaches (see Fig. 1) (Khaksar et al. 2015). For the Optimized Classic Approaches, the robot is considered as a single point in the space. It includes three sub-group methods, namely, the Potential field method (Khatib 1986), the Heuristic Search method (Knuth 1977) and the Sampling Based Algorithm (LaValle 1998). The Evolutionary and Hybrid Approaches are divided into two sub-group methods, namely the Artificial Intelligence and Hybrids. In the Artificial intelligence sub-group many evolutionary algorithms are included, as the Genetic algorithm (GA) (Yun et al. 2011), Ant Colony Optimization (ACO) (Di Caro and Dorigo 2004), Reinforced Learning (Jaradat et al. 2011) and Particle Swarm Optimization (PSO) (Eberhart and Kennedy 1995). The hybrid approaches combine different evolutionary algorithms for better result, we can cite the ACO-PSO (Gigras et al. 2015), the fuzzy logic with the PSO (PSO-Fuzzy), the genetic algorithm with fuzzy logic (GA-Fuzzy), the fuzzy logic with neural network (Neuro-Fuzzy) (Khaksar et al. 2013).

The most important criterion is the search mechanism which is responsible of defining a path that assumes the safety, optimal travel time and low energy consumption for the UAV and defines how it will navigate to the target position. It can be offline, online (Raja and Pugazhenthi 2012) or hybrid (Cao et al. 2018) that handle the optimized classic, and the evolutionary, and hybrid approaches. The offline search needs the knowledge of the static environment and the robot will execute the pre-planned path. With online search, the environment is unknown and the path is re-planned in real-time according to new information acquisition of the surrounding dynamic environment. The Hybrid search combines both offline and online search mechanisms to plan and re-plan a path within the dynamic environment.

Fig. 1
figure 1

Classification of path planning methods

Particularly, there are more challenges to adapt these methods to UAVs path planning. In the dynamic urban environment, a UAV would be possible to crash against the unexpected obstacles because of the dynamic and uncertain environment constraints. Although re-planning can be leveraged to mitigate the uncertainty during flying, the challenge is to generate a feasible trajectory in real-time with limited on-board computational resources and deal with the sudden changing in the surroundings within limited sensing range. In this paper, we propose to tackle this issue. Our solution is a multi-objective hybrid search path planning method to find an optimal path for a UAV flying in dynamic urbain environment, so that it can avoid any present obstacle, whether static or dynamic. The optimality of the trajectory is centered essentially around two objectives: the travel time and the safety.

The main contributions of this paper can be summarized as follows:

  1. 1.

    We use the graph properties and a uniform Cartesian deterministic sampling scheme to represent the urban environment in a 2D space. A grid map is constructed where each cell is mapped with a node of the graph to define the free spaces and capture both static and dynamic obstacles.

  2. 2.

    We design a risk map model to define the velocity and cost of each point in the environment. Specifically, a cost distribution map is constructed offline based on the Fast Marching Square [FM\(^{2}\) (Valero-Gomez et al. 2013)] method which incorporates the static obstacles. And, a dynamic risk map is developed to define the unexpected obstacles that are not available in the geography map. The dynamic risk map is constructed online during the fly based on the safety distance and the perception range of the UAV.

  3. 3.

    A new method is proposed to solve the formulated multi-objective path planning problem where the travel time and safety are considered. Two algorithms are introduced for both search mechanisms (offline and online) to find the optimal path. The offline search is to plan a Pareto optimal path of avoiding static obstacles based on the cost distribution map. The online search is exploited to re-plan an optimal path avoiding the dynamic and unexpected obstacles based on the online constructed risk map of unexpected threats.

  4. 4.

    A real urban environment test is performed in addition to the simulation experiments to evaluate the efficiency of the MOHPP method in the real world.

This paper is structured as follows: in Sect. 2, we discuss the related work. In Sect. 3, we present the generic basics on which the proposed method is based. The detailed design and implementation of our method is presented in Sect. 4. We give the experimental results in Sect. 5 and conclude the paper in Sect. 6.

2 Related work

Recently, several works have been developed to address the multi-objective path planning problem for UAVs, and different path planning algorithms have been proposed. For example, in Wu et al. (2018), Yang et al. (2015), Macharet et al. (2010), Fu et al. (2012), multi-objective path planning methods (MOPP) for UAVs based on the evolutionary algorithms are proposed to find a path avoiding static obstacles in the environment. In Mittal and Deb (2007), authors proposed a 3D path planner for UAVs using multi-objective Evolutionary algorithms. Particularly, the NSGA-II algorithm with an objective function which considers the length and safety of the path. Meanwhile, a B-spline curved is applied to represent the generated path, making the control points as the decision variable of the genetic algorithm. In Roberge et al. (2013), authors attempted to compute the quasi-optimal paths in 3D complex environment using the genetic algorithm (GA) and the particle swarm optimization (PSO), reducing the execution time by adopting the “single program, multiple-data” parallel programming technique, which ensures a real-time solution. A multi-objective \(A^{*}\) is applied in Hernández-Hernández et al. (2014) to plan routes of UAV, where travel time, path angle, energy consumption and area deviation are considered. Authors in González et al. (2016) proposed a multi-objective approach for UAVs to find the optimal path in a 3D environment with static obstacles using the FM\(^{2}\) method. In addition, authors in Chen et al. (2016) applied modified central force optimization algorithm to solve the MOPP problem in 3D environment. Furthermore, authors in Hao et al. (2017) developed a multi-objective path planner in 2D space where the elastic constraint method for multi-objective optimization is applied to find an optimal solution towards the travel time and the energy consumption.

These proposed methods (Wu et al. 2018; Yang et al. 2015; Macharet et al. 2010; Fu et al. 2012; Mittal and Deb 2007; Roberge et al. 2013; Hernández-Hernández et al. 2014; González et al. 2016; Chen et al. 2016; Hao et al. 2017) are practical to plan path but they consider only static obstacles without dynamic ones.

Other works are proposed to extend the solution to MOPP in dynamic environment. In Wu et al. (2011), a grid based multi-step A\(^{*}\) is proposed for path planning in dynamic 4D environment (three spatial and one time dimensions) using a variable successor operator to find the least cost paths enabling the track length, angle and velocity trajectory. Furthermore, by leveraging variable successor operator to impose the multi-resolution lattices structure on the search space. Authors in Wen et al. (2017) considered uncertainties of threats, vehicles’ motions and observations, and then designed an online path planning framework by integrating a sub goal selector, a sub task allocator and a local path planner. In Lin and Saripalli (2015), a multi-objective online path planning algorithm is proposed for UAVs collision avoidance. The algorithm is based on sampling intermediate way-point randomly and collision check using the reachable set.

All these methods (Wu et al. 2011; Wen et al. 2017; Lin and Saripalli 2015) focus only on the online path planning and do not explore offline informations as the geography map. Hence, the optimality of the global path is not guaranteed.

An hybrid path planning (offline and online) is proposed in Yang and Yoo (2018), authors developed a new optimal flight path planning mechanism for UAV data acquisition in wide IoT sensor networks by using multi-objective bio-inspired algorithms. In Pehlivanoglu (2012), authors proposed an evolutionary algorithm based Offline/Online path planner for UAV navigation in 3D rough terrain environment. In addition, in Primatesta et al. (2018) a hybrid approach is proposed to find minimum risk path for UAVs. A risk-map with assessment method combining layers related to the population density, the sheltering factor, no-fly zone and obstacles is generated to quantify the risk of a specific area. A risk-aware path planning based on the well-known Optimal Rapidly-exploring random tree is applied to retrieve the optimal path combining offline and online search. Furthermore, A multi-objective path planning (MOPP) framework is proposed in Yin et al. (2018) to explore a suitable path for a UAV operating in a dynamic urban environment.

Evolutionary algorithms cited in Yang and Yoo (2018), Pehlivanoglu (2012) suffer from the premature convergence problem, since the first population generates randomly the individuals (solutions) which lead to large quantities of unfeasible paths, and they cause more computational time or meaningless work. The computational time of the method in Primatesta et al. (2018) is high due to the Rapidly-exploring Random Tree (RRT\(^{*}\)) method’s characteristics. In Yin et al. (2018) the resulted path is zigzagging and not smooth, this causes the loss of efficiency of the method in the real world.

It can be seen that these proposed methods do not fully address the multi-objective path planning problem under the real urban environment. In order to remedy this, in our approach, multi-objective cost-determinant variables are taken into account (safety, travel time, and distance for online search). An hybrid (offline/online) path search mechanism is developed to derive the set of optimal paths considering both the static and dynamic obstacles of the real world.

3 Preliminaries

In this section, we define some generic bases on which the proposed method is based. We explain the model of the environment, the multi-objective path planning problem formulation and the Fast Marching Method, which is a base for the definition of the optimal path.

3.1 Environment modeling

The environment is described by a 2-D space graph represented by a three-tuple \( \langle G,P_{start},P_{target} \rangle \), where \(G = (N,A,c)\) represents the space graph, N denotes a set of nodes (points) and \(P_{start}\in N\) and \(P_{target}\in N\) are, respectively, the set of the start nodes and target nodes. A is the set of arcs between nodes of G, and \(c:A \longrightarrow \) \(R^{k}\) represents the path cost function, where K is the number of objective functions. A uniform Cartesian deterministic sampling scheme is utilized to construct the graph G. As a result, each node \(p\in N\) is mapped uniquely to a cell of the grid. Hence, the p refers simultaneously to both the cell and to a point located in the center of the cell (see Fig. 2).

Fig. 2
figure 2

2-D space graph

3.2 Multi-objective path planning problem

The path planning under dynamic urban environment is constrained by a set of internal conditions (energy consumption, sensor’s capacities,...) and a set of external conditions (buildings, no-fly zones, other UAVs, Birds,...). In our case, we chose to deal with these issues targeting two key objectives: safety and travel time.

Safety The safety objective is defined in this paper with the collision avoidance criterion which needs a separation distance from obstacles to provide a safe path to the UAV. So, the closer the point is from the obstacle, the lowest the safety level is. Furthermore, there is uncertainty in the position, velocity and direction of the dynamic obstacle because of potential sensor error which may lead to collision risk.

Travel time This is another crucial objective for the mission itself. The plan of the mission should be the shortest in time. The travel time is restricted typically by the cruise velocity at each node.

The solution to the multi-objective optimization problem (with two objectives) is to find a path p ,in a graph \(G = (N,A,c)\), between a source and target points with the minimal total cost W. Let \(c_{i,1}\) and \(c_{i,2}\) be, respectively, the safety and travel time cost functions at arc \(i \in A\). Let \(l_{j}(p) = \sum _{i\in p} c_{i,j}, j\in \lbrace 1,2\rbrace \), be the total cost in a path for the \(j{th}\) objective.

For p to be an optimal path compared to any other path q in G, the following conditions should be verified:

$$\begin{aligned} {\begin{matrix} &{}\forall j\in \lbrace 1,2\rbrace , l_{j}(p) \le l_{j}(q), and\\ &{}\exists i\in \lbrace 1,2\rbrace , l_{i}(p) < l_{i}(q) \end{matrix}} \end{aligned}$$
(1)

Solutions that are not dominated by any other solutions are Pareto Optimal (denoted by a Pareto set P). p is a Pareto optimal path of the Pareto optimal set P, which has the minimal total cost W with a weight coefficient \(\alpha \):

$$\begin{aligned} W =\min _{p\in P} \alpha .l_{1}(p)+(1-\alpha ).l_{2}(p) \end{aligned}$$
(2)

3.3 The fast marching method (FMM)

The fast marching method (FMM) is a particular case of the Level Set Methods developed initially by Osher and Sethian (1988). It is an efficient computational algorithm for modeling and tracking the motion of a physical wave interface (front) denoted as \(\Gamma \). Within FMM, the front is called interface. The interface can be a flat curve [two-dimensional (2-D)] or a three-dimensional (3-D) surface, but the mathematical model can be generalized to n dimensions.

Considering a gridmap representing the real environment where obstacles are labeled 0 and free spaces 1. The FMM calculates the time T required for a wave to reach each point on the gridmap. The wave can be originated from more than one point, and each point generates a wave. The point where the wave is originated has a time \(T =\) 0.

In the context of Fast Marching, the front \(\Gamma \) is supposed to move in the normal direction with a non-negative speed value which can vary over time. At each instant, the front’s motion is described with the Eikonal equation (Osher and Sethian 1988):

$$\begin{aligned} 1 = {F(x)\vert \nabla T(x)\vert } \end{aligned}$$
(3)

where x is the position, F(x) is the expansion speed at that position, and T(x) is the time the wave interface needs to reach x.

The magnitude of the gradient of the time function is inversely proportional to the velocity

$$\begin{aligned} \frac{1}{F} = \vert \nabla T\vert \end{aligned}$$
(4)

The T(x) function generated by a wave that expands from one source point has one global minima at the source and no local minima. As the expansion speed is positive (\(F>0\)), the wave only grows. Hence, points farther from the source have a greater T (T is single valued as \(F>0\)).

Osher and Sethian (1988) proposed a discret solution for the Eikonal equation. In 2-D, the area is discretized using a grid map. The intersection of row i and column j of the grid corresponds to a point \(p(x_{i},y_{j})\) of the real environment, and the discretization of the gradient \(\nabla T\), according to Osher and Sethian (1988), leads to the following equation:

$$\begin{aligned} \left\{ \begin{array}{l} max\left( D_{ij}^{-x}T,0\right) ^{2}+min\left( D_{ij}^{+x}T,0\right) ^{2}\\ +max\left( D_{ij}^{-y}T,0\right) ^{2}+min\left( D_{ij}^{+y}T,0\right) ^{2} \end{array}\right\} =\frac{1}{F_{ij}^{2}} \end{aligned}$$
(5)

According to Osher and Sethian (1988), a simpler but less accurate solution of (5) can be expressed as follows:

$$\begin{aligned} \left\{ max\left( D_{ij}^{-x}T,-D_{ij}^{+x}T,0\right) ^{2}+max\left( D_{ij}^{-y}T,-D_{ij}^{+y}T,0\right) ^{2}\right\} = \frac{1}{F_{ij}^{2}} \end{aligned}$$
(6)

where

$$\begin{aligned} D_{ij}^{-x}&= \frac{T_{i,j} - T_{i-1,j}}{\delta x}&D_{ij}^{+x}&= \frac{T_{i+1,j} - T_{i,j}}{\delta x}\nonumber \\ D_{ij}^{-y}&= \frac{T_{i,j} - T_{i,j-1}}{\delta y}&D_{ij}^{+y}&= \frac{T_{i,j+1} - T_{i,j}}{\delta y} \end{aligned}$$
(7)

\(\delta x\) and \(\delta y\) are the spacing grid in the x and y directions. Substituting (7) in (6) and letting

$$\begin{aligned} T&= T_{i,j}&T_{x}&= min\left( T_{i-1j},T_{i+1j}\right)&T_{y}&= min\left( T_{ij-1},T_{ij+1}\right) \end{aligned}$$
(8)

We can rewrite the Eikonal equation in a discretized 2-D space as follows:

$$\begin{aligned} max\left( \frac{T-T_{x}}{\delta x},0\right) ^{2} + max\left( \frac{T-T_{y}}{\delta y},0\right) ^{2}&= \frac{1}{F_{ij}^{2}} \end{aligned}$$
(9)

As we assume that the speed of the front is positive (\(F>0\)), T must be greater than \(T_{x}\) and \(T_{y}\) whenever the front wave has not already passed the coordinates ij.

We can solve (9) in three steps. First, we solve the following quadratic

$$\begin{aligned} \left( \frac{T - T_{x}}{ \delta x} \right) + \left( \frac{T - T_{y}}{ \delta y} \right) = \frac{1}{F_{ij}^{2}} \end{aligned}$$
(10)

If \(T>T_{x}\) and \(T>T_{y}\) [taking the greater value of T when solving (10)], the obtained value is the correct solution for equation (9). Else, if \(T<T_{x}\) or \(T<T_{y}\), from equation (9), the corresponding member of \((\frac{T-T_{x}}{\delta x},0)\) is 0, and hence, (9) is reduced to

$$\begin{aligned} \left( \frac{T-T_{x}}{\delta x}\right)&= \frac{1}{F_{ij}} \end{aligned}$$
(11)
$$\begin{aligned} \left( \frac{T-T_{y}}{\delta y}\right)&= \frac{1}{F_{ij}} \end{aligned}$$
(12)

depending on the final value of T.

The equation (9) can be solved iteratively over a gridmap. To do so, the cells of the gridmap must be labeled as one of the following types:

  • Unknown Cells with unknown value of T (the wave has not reached the point).

  • Narrow or Narrow band Candidate cells to be part of the front wave in the next iteration. They are assigned a T value that can still change in the future iterations of the algorithm.

  • Frozen Cells that have been passed over by the wave and, hence, their T value is fixed.

The algorithm (see Algorithm1) has the following steps (an illustration is associated to it in Fig. 3):

  • Initialization The algorithm defines \(T = 0\) for the set of cells where the wave is originated, these cells are labeled Frozen. Afterward, it labels all the Manhattan neighbors as Narrow, computing T for each of them.

  • Main loop: In each iteration, the algorithm solves the Eikonal equation (9) for the Manhattan neighbors of the narrow cell (that are not Frozen) with the lesser T value, then label this cell Frozen. The narrow band maintains an ascendent ordered list of its cells according to the value T.

  • Finalization When all the cells are Frozen (the narrow band list is empty), the algorithm finishes.

figure a
Fig. 3
figure 3

Iterative wave expansion with one point source

4 Proposed method

The MOHPP method introduces first the cost distribution map which defines the velocity and the cost of each point in the environment. This map is used to plan a path that meets two objectives: the safety and the travel time. The cost distribution map is exploited by the offline search mechanism. The dynamic risk map is constructed online when detecting unexpected obstacles concerning both the range perception and the safety margin of the UAV. The dynamic risk map is used with the online search mechanism.

The solution for the multi-objective (Safety and Travel time) optimization problem is to find an optimal path p between two points on the graph G(NAc). Every arc of A has two non-negative costs denoted \(c_{i,t}\) and \(c_{i,s}\) representing the travel time and the safety respectively. This is possible by exploiting the FM\(^{2}\) and the A\(^{*}\) algorithm for offline search and online search respectively.

4.1 Cost distribution map

The safety of the travel is an important criterion to ensure the completion of the mission. For this aim, we need to define the different obstacles that appear in the map considering the static ones. Hence, we attribute the allowed velocity and the cost at each point of the grid map. To solve this problem, we use a variant of the Fast Marching Method over the original map (grid map) which is the Fast Marching Square method (FM\(^{2}\)) (Valero-Gomez et al. 2013).

The result of FMM is a gridmap with T assigned for each point, but the value of the speed of each point remains zero (0) at obstacles, and one (1) in free spaces. However, we need different velocities on the different points: if the UAV passes near an obstacle, it requires a lower speed for the security. The Fast Marching Square (FM\(^{2}\)) assumes the relation between security distance and velocity.

The operating principle of the FM\(^{2}\), as given in Valero-Gomez et al. (2013), lies in the fact that it applies the FMM twice. In the first application, over the gridmap, the FM\(^{2}\) attributes a speed value for each point in the map (the line 1–2 of Algorithm 2). All the vertices of the obstacles are the wave source, and the T value represents the velocity. As result, a grid map with a relative speed value assigned to each point of the graph.

We need to define a separation distance from obstacles where the velocity should be reduced to guarantee the safety of the UAV. To do, we use a saturation coefficient \(\alpha \) (\(0.00< \alpha < 1.00\)) to define the safety level. By varying the value of \(\alpha \), the separation distance varies proportionally to the farthest distant point from obstacles (point with highest T value in the first execution of FMM). When \(\alpha = 1.00\), the separation distance should be the same as the farthest distant point (the highest safety level considered). When \(\alpha = 0.00\) implies that the safety level consideration is zero.

If we suppose that the T value of each point in the obtained map is the corresponding velocity (V), the latter should be scaled and normalized according to the maximum allowed speed (\(V_{max}\)) and the safety level. The scale formulation is given in Eq. (13) and the normalization in Eq. (14).

$$\begin{aligned}&\forall p_{i = 0,N} \in P, \qquad V_{pi} = \dfrac{T_{pi}}{T_{max}} \end{aligned}$$
(13)
$$\begin{aligned}&Vel_{pi} = {\left\{ \begin{array}{ll} \dfrac{V_{pi}}{\alpha }*V_{max} &{} \text {if}\,V_{pi} < \alpha \\ V_{max} &{} \text {otherwise} \end{array}\right. } \end{aligned}$$
(14)

where P is the set of the points in the map, pi a point in P, \(T_{pi}\) the related defined velocity, \(V_{pi}\) the scaled velocity and \(Vel_{pi}\) is the normalized velocity.

The code implementation is given in line 3–11 of Algorithm 2.

The second application is to assign the arrival time (denoted \(T'\)) for each point over the gridmap, after the saturation process, from a source point ps until reaching the destination pd (line 12 in Algorithm 2). The arrival time value (\(T'\)) of obstacles is infinity. The hole process of cost distribution map (CDM) construction is illustrated in Fig. 4.

Fig. 4
figure 4

Process of CDM construction

figure b

4.2 Dynamic risk map

The computational time of the process of defining static obstacles is relatively high for real time treatments. Hence, it is not suitable in case of dynamic and unexpected obstacles that need a real time reaction of the UAV. The solution is to construct a dynamic risk map in real time, with low computation time, where the new obstacles will be spotted.

We construct a dynamic risk map (DRM) according to two criteria: the perception range and the safety margin. We define the dynamic risk map as a set of nodes, within the perception range of the UAV, that are identified as new threats by the embedded sensors. In addition, we defined a safety margin from the new obstacles at which the UAV should brake to avoid the collision. The process is illustrated in Fig. 5

  1. 1.

    Perception range UAV needs to detect surrounding environment while performing its mission. Let us denote R the perception range radius of the embedded sensors centered at the UAV. It can take the following form

    $$\begin{aligned} \left( x_{c} - x \right) ^{2} + \left( y_{c} - y \right) ^{2} \le R \end{aligned}$$
    (15)

    where (xy) is an arbitrary point within R, and \(( x_{c}, y_{c})\) the current position of the UAV.

  2. 2.

    Safety Margin when an unexpected obstacle is detected the UAV takes an emergency brake as avoiding measurement. We call the emergency brake distance SafetyMargin (denoted \(d_{sm}\)). Next, the dynamic risk map is constructed according to the security distance:

    $$\begin{aligned} I = \left\{ \begin{array}{ll} + \infty \quad d_{c} \le d_{sm}\\ 0 \qquad else \end{array} \right. \end{aligned}$$
    (16)

    where \(d_{c}\) is the straight distance between the UAV and the unexpected obstacle, I is the danger index (points that have distance \(d_{c} \le d_{sm}\) take the highest value).

Fig. 5
figure 5

Process of DRM construction

4.3 Offline search

To compute the global optimal path between \(p_{start}\) and \(p_{goal}\) over the cost distribution map, the maximum gradient direction should be followed from \(p_{start}\) to \(p_{goal}\). As every cell has the lowest possible value \(T_{i}\) assigned, the path returned will be optimal. The maximum gradient direction is computed applying the Sobel operator over the grid map, and this from the start point until reaching the global minima which is the goal point.

Starting at the initial point, the path is calculated iteratively, the Sobel Operator calculates approximations of the gradients on the horizontal and vertical orientations (Eq. 17).

$$\begin{aligned} grad_{x} = \left[ \begin{array}{ll} -1\quad 0\quad 1\\ -2\quad 0\quad 2\\ -1\quad 0\quad 1 \end{array} \right] *T \qquad \qquad grad_{y} = \left[ \begin{array}{ll} -1\ -2\ -1\\ 0\qquad 0\qquad 0\\ 1\qquad 2\qquad 1 \end{array} \right] *T \end{aligned}$$
(17)

where T is the cost, \(grad_{x}\) and \(grad_{y}\) are the gradient values on the two dimensions x and y respectively.

At each point \(p_{i}\), the gradient is computed on the X-direction (\(grad_{ix}\)) and Y-direction (grad iy), thus the magnitude and the direction (\(mod_{i}\) and \(\alpha _{i}\) in Eq. 18) can be computed. From \(p_{i}\) is computed \(p_{i+1}\) successively until reaching the goal following the direction in which the time is increased the most.

$$\begin{aligned} mod_{i}&= \sqrt{grad_{ix}^{2} + grad_{iy}^{2}}&\alpha _{i}&= \arctan \left( \frac{grad_{iy}}{grad_{ix}}\right) \nonumber \\ p_{(i+1)x}&= p_{ix} + step.\cos (\alpha _{i})&p_{(i+1)y}&= p_{iy} + step.\sin (\alpha _{i}) \end{aligned}$$
(18)

A highlight result is given in Fig. 6 where the maximum gradient is followed from a start point marked with black “X” in direction to the global minima marked with white “O”.

Fig. 6
figure 6

generated path by applying gradient descent

4.4 Online search

The offline search mechanism guarantees the optimality of the path whatever the type of the static obstacle in the environment. However, when an unexpected obstacle appears in the detection area, the path will be ineffective and should be re-planned. The primary aim in this case is to generate quickly a path to avoid the unexpected obstacles. So, the best way to get the UAV out of the danger zone is to generate a local optimal path of avoiding. The offline search is done over the global map (without new obstacles), and, its computational time is relatively high which is not suitable for the real time treatments. As a solution, we developed an online search mechanism to generate a path of avoiding the dynamic threats within the detected area. The online search is based on the \(A^{*}\) algorithm, the cost distribution map informations to guide the search direction instead of the straight-line search, and a cut down mechanism to accelerate the search efficiency.

The \(A^{*}\) algorithm uses a cost heuristic function denoted f(p) to identify the order in which the search treats the points in a tree, which is computed with

$$\begin{aligned} f(p) = g(p) + h(p) \end{aligned}$$
(19)

where g(p) is the real cost from the start to the current point, h(p) is a heuristic cost from the current to the goal. The classic \(A^{*}\) utilizes a straight-line to the goal for the heuristic h(p). In our case, we attribute to h(p) the costs of nodes generated by the offline process. In addition, a search space cut-down mechanism is proposed to guarantee the efficiency of \(A^{*}\) within the ONPS mode even when the geography map is large, and the start point is far from the goal point.

We use a two-steps cut down mechanism: If the straight-line between the current point and the goal does not intersect with the dynamic threat zones generated by unexpected obstacles, then check if there is no dynamic obstacles within the UAV’s safety range (\(d_{sm}\)). Hence, terminate the online search process. If the UAV’s safety range (\(d_{sm}\)) contains the dynamic threats, the ONPS mode will re-plan a path to get far from that zone. When the goal point is far from the start point, the search space is reduced and the efficiency of online search process is enhanced. The pseudo-code of the online search process is summarized in Algorithms 3 and 4.

figure c
figure d

The global method (as given in Algorithm 5) which groups the different algorithms to plan the path takes as inputs the geographic map, the start and goal points’ coordinates, the maximum velocity of the UAV, the desired saturation coefficient, and the safety margin for the dynamic risk map. The first step consists of generating the cost distribution map by the first execution of the FMM method. After that, the offline search generates the global optimal path, the start point is added to the executed path, current position is initialized to start and the boolean variable which defines if an unexpected obstacle is detected is set to false. Then the first movement is done by the UAV (lines 2–4 in Algorithm 5). The while loop is the main process that allows the UAV to move to the target position (lines 7–19 of Algorithm 5). In this loop, a process of checking the presence of unexpected obstacles in the sensed environment is done. If no unexpected obstacle appears, the next position is the one given by the offline search. Else we construct the corresponding dynamic risk map and switch to the online search, hence the UAV will follows the different positions calculated in real time until it avoids the new obstacles or reaches the goal.

figure e

5 Experimental results

In this section, we discuss results obtained from different experiments that have been done as part of the evaluation of our approach. Namely, the synthetic simulation on the graphical interface, and the Software-In-The-Loop experiment on a quadri-rotors. In addition, a real test is done with a real quadri-rotors model X (video available inFootnote 1). We use specific parameter setting for each environment and a quadri-rotors model X for real tests.

5.1 Parameter setting

We conducted two types of experiments to evaluate our method. The Algorithms are programmed with Python language in both cases. The implementation steps are as follows:

Setup for simulated scene

  • Hardware We used a computer desktop with Intel(R) Core(TM) i5-7400 CPU @ 3.00GHz and 16 GB of memory.

  • Simulated environment ad map generation The operating system used was Linux Ubuntu 16.04 LTS. We used TKinter library from Python to generate the simulated environments, where two binary maps with 200 \(\times \) 150 lattices are generated with resolution of Dx:Dy = 1:1 pixel (corresponding to 1:1 m). We used matplotlib library in Python to visualize the different simulation results (velocity profile, travel time and safety level).

  • Parameters setup for the MOHPP method Our method takes as parameters a saturation coefficient to define a safety level (0.00 \(< \alpha<\) 1.00), maximum velocity as the property of the maximum speed of the UAV (set to 1 m/s) and a safety margin that the UAV should take when detecting an unexpected obstacle (set to 4 m).

Setup for the real scene

  • Hardware We used a quadri-rotors model X equipped with a Pixhawk card controller and Ardupilot system as firmware. A Raspberry-Pi (RPi3 Model B) as a companion computer. We use the DroneKit-API on the RPi3 to communicate commands with the Pixhawk controller via MAVlink messages. The MOHPP method is implemented on the companion computer. To visualize and track the UAV movements, we used the telemetry radio to send messages to the Mission Planner ground control station. Pictures of the UAV are given in Figs. 7 and 8 illustrates the communication scheme, and Table 1 gives the details of the hardware components.

  • Realistic environment definition In this setup, the environment is a region on the Satellite Map with resolution of 200 \(\times \)150 m. We extracted a binary map from the Satellite map and divided it into disjoint lattices with resolution set to Dx:Dy=1:1 pixel (corresponding to 1:1 meter of the Satellite map). All the buildings are pointed out as static obstacles.

  • Parameters setup for the MOHPP method Our method takes the same number of parameters as in the simulated scene; a saturation coefficient to define a safety level (0.00 \(< \alpha<\) 1.00), maximum velocity as property of the maximum speed of the UAV (set to 1 m/s) and a safety margin at which the UAV should brake when detecting unexpected obstacle (set to 5 m). The coordinates of the start and end points are fixed, respectively to (75, 99) and (50, 20).

Fig. 7
figure 7

Quadri-rotors model X

Fig. 8
figure 8

Communication scheme

Table 1 UAV components details

5.2 Evaluation

In the following, we evaluate the ability of our approach to deal with the static and dynamic obstacles of the urban environment. First, we evaluate the influence of the saturation coefficient on the safety level and the travel time over the static obstacles. Second, we evaluate the effect of the perception range on the online search mechanism to avoid the unexpected obstacles.

5.2.1 The simulated scene

In this setup, we generate two binary maps of scale 200 lattices × 150 lattices, the lattice resolution is 1:1 m.

Fig. 9
figure 9

On (a), a binary map with static obstacles (black). On (b), a binary map with both static and dynamic (grey) obstacles

- Effects of the saturation In this experiment we constructed a cost distribution map with different saturation values \(\alpha \) (the original map is shown in Fig. 9a) in order to evaluate the influence of the saturation on the velocity and the length of the path. The result shown in Fig. 10 illustrates the final result of the first wave propagation of FM\(^{2}\) and the saturation process (formulated in Eqs. 13 and 14) to define the relative speed at each point in the map according to the value of \(\alpha \) (we precise that the lighter the color is, the closer the velocity is to the maximum allowed value). In Fig. 10a with \(\alpha \)=0.15, we can observe that the points closest to the obstacles in the map have a reduced velocity and the others at the maximum velocity. Compared to results in Fig. 10c with \(\alpha = 0.75\), more points have reduced velocity, this is due to the larger separation distance defined by \(\alpha \) where the velocity should be reduced.

Fig. 10
figure 10

Saturated velocity map according to values of \(\alpha \)

We called the MOHPP method hundred (100) times with different \(\alpha \) values to obtain the safety level and the travel time tradeoff curve shown in Fig. 11 where the X-coordinates are the safety level and the Y-coordinates represents the travel time profile. The blue curve in Fig. 11 is the efficient path set P got from the execution of the MOHPP, and the red curve is the Pareto-optimal path set. The safety index of a point n (denoted \(I_{n}\)) is calculated according to the first propagation of the wave. Indeed, as the obstacles are the wave source expansion, the value of \(I_{n}\) is 0 and increases proportionally to the wave propagation. Thus the farthest point has the highest safety index. The total safety index of a path \(p\in P\) is expressed as follows:

$$\begin{aligned} I_{p} = \sum _{p} I_{n} \end{aligned}$$

Furthermore, we calculate the risk index as: \(\log _{10}(I_{p})\).

The total travel time t of a path p (with distance \(d=1\)) is expressed as follows:

$$\begin{aligned} t_{p} = \int _{p} \frac{1}{Vel_{n}} dn \end{aligned}$$

where \(Vel_{n}\) is the cruise velocity at point n.

Fig. 11
figure 11

Travel time and safety level tradeoff curve under a synthetic obstacles scenario

Figure 12 shows the final Cost Distribution Map (after the second application of the FM\(^{2}\) over the velocity map illustrated in Fig. 10) with the arrival time T set for each point. The coordinates of the start point (marked with the red ’X’) and the goal (marked with pink ’X’) are respectively (90, 10) and (70, 120). We can see the effect of the defined velocity on the wave propagation speed. Indeed, when \(\alpha \)==0.15 (shown in Fig 10a), most of the points are at their maximum velocity, this allows a high wave propagation speed which makes the arrival time cost T low. Compared to results in Fig. 12c, the propagated wave takes a longer time to arrive at the destination, this is due to the reduced cruise velocity assigned to the points (Fig. 10c) which reduces the speed of the wave propagation.

Fig. 12
figure 12

CDM map with arrival time T assigned at each point

Fig. 13
figure 13

OFPS results and the corresponding velocity profiles

The results of the execution of OFPS algorithm over the illustrated cost distribution maps in Fig. 12 are plotted in Fig. 13. The blue curve in the figure is the trajectory and the cyan circle is the detection range of the UAV. The corresponding travel time for the different saturation coefficient is given in Table 2. As shown, different trajectories with their velocity profiles are computed depending on the value of \(\alpha \). Indeed, the aim of the OFPS is to follow the maximum gradient direction from a start point to the destination with the global minima \(T=0\). To do so, the direction that reduces the T value should be chosen at each step, which is referred, simultaneously, to the neighbor with the highest cruise velocity. We can see in Fig. 13a, with \(\alpha =0.15\), the path goes near obstacles as the maximum gradient is achieved at a low separation distance. In addition, the cruise velocity profile (shown in Fig. 13d) is almost at the maximum allowed (1 m/s) due to the high consideration of travel time criterion in relation to safety level. That leads to shorter travel time (290s) and high risk index (17.70). Compared to Fig 13c, the path goes far from obstacles, as \(\alpha \) defines a large safety distance which implies the maximum gradient to be achieved only with points that are far from obstacles as they have the lowest T and the highest cruise velocity. Furthermore, the cruise velocity profile, in Fig 13f, is almost under the maximum allowed (1 m/s), due to the high safety level consideration. This results in longer travel time and path length (1167 s) with a low risk index (5.86).

We can resume that shorter travel time leads to higher risk level, and high coefficient value results to safer trajectory with longer travel time which is due to the contradiction of two objectives. Fortunately, the MOHPP method can effectively return an optimal path that corresponds to the needed criteria weighting.

Table 2 Travel time and Risk index numerical results

- Effects of the perception range In this experiment, we evaluate the ability of our approach to deal with unexpected obstacles. The original map is given in Fig. 9b where an unexpected obstacle is involved. The coordinates of the start and the end points are respectively (85,50) and (85,180). In addition, we set \(\alpha \) to 0.3.

Fig. 14
figure 14

Process of exploring a path with perception range = 10 m

Fig. 15
figure 15

Process of exploring a path with perception range = 30 m

Figure 14, Fig. 15 depict intermediate results of avoiding known and unexpected obstacles by MOHPP method. In these figures, the circle with cyan color is the perception range, with safety margin of 4 m. The black color indicates the presence of static obstacles, the grey color is the unexpected obstacle, and the maroon color is the detected dynamic threat zone. The blue curve is the offline generated path and the magenta color is the online path followed by the UAV. The red lines denote the computed trajectory by \(A^{*}\) algorithm.

The results show that the method can effectively avoid known and unknown obstacles, as we can see, the UAV succeeds to detect the unexpected obstacle and re-plan a path that keeps a safety distance which is defined as safety margin.

We note that the surface of the detected area influences directly the online search process. Actually, the ONPS algorithm computes a local optimal path of avoiding the obstacle depending on the perception range radius. When the sensed area is large, more nodes are updated and defined. If they are obstacles, then, the ONPS mechanism computes a path of bypassing with few iterations by executing \(A^{*}\) algorithm (see Fig. 15). With a small sensed area, more iterations are necessary to re-plan the bypassing path which is became unfeasible when new the threats are detected (see Fig 14).

Table 3 Running time of the A\(^{*}\) and DRM process

Table 3 highlights the correlation between the number of iterations and the computation time of the A\(^{*}\), and the computation time of constructing the DRM map within the ONPS mode when the perception range changes. We can see that the number of iterations decreases and the computation time of A\(^{*}\) and DRM increases depending on the perception range. This is due to the number of nodes in the sensed area on which ONPS invokes A\(^{*}\). From range of 30 m, the number of iterations and the run-time of A\(^{*}\) remains the same, because the whole threat is identified. In addition, the computation time of \(A^{*}\) in one iteration within the ONPS mode is less than 3 ms.

In summary, the ONPS mode depends on the perception range of the embedded sensors. The higher the radius, the better we detect the unexpected obstacle and walk around it with few iterations. This implies more computation time. The smaller the radius, the better we reduce the computation time. This implies, more iterations as a small surface can be detected. The efficiency of the cut-down mechanism in ONPS is that the user can choose the desired sensors regardless the real-time constraint since the computation time is always low. That proves the efficiency of our method to deal with the dynamic obstacles in real-time.

5.2.2 Evaluation of MOHPP in a real scene

In this setup, we conducted this experiment under an emulated urban scene using SITL (Software In The Loop) technology, as illustrated in Fig. 16, to certify the feasibility of the MOHPP method in the real world. This scenario is a region’s plan of Satellite Map (33\(^{\circ }\)36\(^{\prime }\)56.9\(^{\prime \prime }\) N 117\(^{\circ }\)06\(^{\prime }\)47.9\(^{\prime \prime }\) W). The map is divided into disjoint lattices with resolution of 1:1 m and all the buildings are extracted. We built a scheme from the real map as shown in Fig. 17. We set the coordinates of the starting point of the UAV to (75th vertex, 99th vertex) and the target point of the UAV at (50th vertex, 20th vertex).

Fig. 16
figure 16

Map from Google maps

Fig. 17
figure 17

schematic diagram of the realistic obstacles

We executed MOHPP hundred (100) times with different \(\alpha \) value (\(\alpha \) from 0.01 to 0.99) to test the effect of the saturation coefficient through the realistic obstacles. In this experiment, the offline search process is tested. We extracted the results to the tradeoff curve in Fig. 18. Two paths are illustrated in Figs. 19 and 20, while the numerical results are reported in Table4.

Fig. 18
figure 18

Travel time and safety level tradeoff curve under a realistic obstacles scenario

Figures 19 and 20 show the experimental test results versus the simulated scene with saturation value of 0.2 and 0.4 respectively. Figure 19a and 20a are the outputs (from the GCS interface) of the followed paths by the quadri-rotors, whilst Figs. 19b and 20b are the outputs of the simulation tests.

Fig. 19
figure 19

Generated path: Experimental test vs. Simulation test with \(\alpha \)=0.2

Fig. 20
figure 20

Generated path: Experimental test vs. Simulation test with \(\alpha \)=0.4

Table 4 Numerical results of the experimental tests

The OFPS search produces interesting results. The real UAV succeeds to follow the same trajectory as the one generated from the schematic diagram for the simulated scene according to the saturation coefficient. In addition, the defined cruise speed at each point is almost respected (with negligible errors) as illustrated in Fig 21. With \(\alpha \)=0.2, a short path is generated at a small distance from buildings with the most of points at their maximum velocity (Fig. 21a). With \(\alpha \)=0.4, a longer path is computed far enough from buildings, and a low cruise velocity is set (Fig. 21b).

Numerical results in Table4 support that a small value of \(\alpha \) generates a path with a minimum travel time and a higher risk index. In other hands, a minimum risk index leads to a longer travel time. In addition, the UAV flight time is little higher than the theoretical computed one, this is due to the accumulated small errors of the UAV’s cruise speed (see Fig 21), also, the data exchange process between the companion computer and the flight controller.

Fig. 21
figure 21

Real UAV’s cruise speed VS. theoretical cruise speed: Fig. 21a corresponds to the test illustrated in Figs. 19, and 21b to the one in Fig. 20

Comparing our solution with the proposed one by Yin et al. (2018) it’s clear that our method is best in term of correlation between the set of criteria and the smoothness of the path. Indeed, the method in Yin et al. (2018) uses the simple bi-variate Gaussian model and the FM method to define the cost of points. The omitted results show that their solution is unable to define a sufficient distance from obstacles even when the safety is highly considered. Moreover, the generated path is zigzagging near obstacles which make it unfeasible. Our approach clearly assumes the needed safety and travel time thanks to the saturation mechanism and the FM\(^{2}\).

5.2.3 Discussion of the results

As a summary of the tests done, we can note the following observations:

  • MOHPP method needs the coefficient \(\alpha \) to determine the non-dominated solution over the travel time and the safety level criteria according to Eqs. 1 and 2. Explicitly, high value of \(\alpha \) implies high security and longer travel time. Low value of \(\alpha \) corresponds to shorter travel time and low security level.

  • According to the results of the real experiment done with a micro quadrotor (the most used UAVs’ category in smart cities) with low acceleration, the theoretical calculated paths and the followed ones are restrictively the same in term of positioning and localisation (as shown in Figs. 19 and 20). A small error is observed for the real flight in relation to the cruise velocity which is due to the embedded material estimation error. Nevertheless, embedding MOHPP into a micro quad UAV guarantees better experience within real smart cities as the similarity=\(98.3 \%\) between the real flight time and the simulated one.

  • The introduction of the enhanced cut-down mechanism to reduce the space search, also by exploring the offline cost to orient the search within the ONPS (discussed in Sect. 5.2.1), can lead the UAV rapidly finding the optimal local path with less memory occupation and low computation time. As supported by results in Table 3, with max run-time of DRM (< 1 ms) and A\(^{*}\) (< 3 ms) the agility of the UAV will be in real-time with the unexpected threats.

  • The method relies heavily on the on-board sensors to avoid the unexpected obstacles. Indeed, the detection area depends on the type of sensors and their perception range. If the perception range is larger, then the detected area is large and the probability to find an optimal local path with few online process iterations is high.

  • The changing of the perception range has no effect on the UAV path obtained through the CDM because the OFPS mechanism uses the prior complete knowledge of known obstacles to generate a global optimal path. Nevertheless, the computational time of the online search mechanism is affected by the perception range; as the number of iterations is reduced when the detection range is high, and vice versa.

  • The MOHPP method can always determine an optimal path whatever the types of obstacles (static and dynamic). For example, when the UAV carries a sensitive or dangerous product, a safe trajectory is suitable; thus, our method can find an optimal path set with high safety level (Pareto-optimal path set with risk index value under 42 in Fig. 18). When the delivery concerns a bag of emergencies, the UAV must reach the destination soon while guaranteeing a minimum safety level. So, our method can also satisfy this requirement as it offers a Pareto-optimal path set with the shorter travel time (Pareto-optimal path set with travel time less than 80 seconds in Fig. 18). In other hands, when both high safety level and optimal travel time are required, our approach can supply a Pareto-optimal path set that meets these expectations (Pareto-optimal path set in Fig. 11 where risk index is between 42 and 45 and travel time is between 80 and 120 s).

6 Conclusion

This paper deals with the path planning problem for UAV under dynamic urban environment. A method, called MOHPP, concerning two objectives, namely travel time and safety level, has been proposed. In this method, a cost distribution map is established offline to indicate the main static obstacles in the geography map, and define the cost of each point in the map. A dynamic risk map is constructed when detecting unexpected obstacles during the fly. Then a joint offline and online search algorithm has been developed to plan a path to the destination. The offline search is exploited to find the shortest path with static obstacle avoidance based on the offline cost distribution map, and the online search is exploited to avoid unexpected obstacles according to the temporarily online dynamic risk map. The different results of synthetic and realistic experiments (under SITL) show that the MOHPP method is efficient to return always the optimal path, which meets the safety level and the shortest travel time.

As future work, we will focus on the extension of the MOHPP method to the dynamic 3D environment. Given the large number of nodes to be treated in such an environment, it would be necessary to optimize the response time of the method. In addition, we will work on enhancing the accuracy of the wave propagation along the diagonal direction to reduce the errors of the Eikonal equation. Furthermore, we will try to integrate other optimization criteria, such as, the wind direction and fuel consumption, to allow the method to handle more environmental factors and improve its efficiency in a real world environment.