1. Introduction
Small unmanned aerial vehicles (UAVs) have considerably evolved and are increasingly applied in many fields, such as agriculture [
1,
2], monitoring [
3,
4], transportation [
5,
6], delivery [
7,
8], and rescue [
9,
10], necessitating additional research on the use of UAVs for mobile robotics, photogrammetry, and monitoring, to name but a few. The core advantage of using UAVs is that they can operate and execute missions in hazardous and dangerous situations. However, certain safety challenges must be considered when integrating UAVs, including attention cost, psychological impact, and physical risks [
11]. As such, safety is the most-debated topic of designing and using UAVs [
12]. The reason why UAVs are not yet safe, especially indoors, is that they still have flaws such as poor environmental perception and low strain capacity, which means that during autonomous UAV flight in complex environments, safety hazards cannot be completely avoided, posing potential threats to life and property.
Different UAV models, each with their own unique traits, are appropriate for different application scenarios. Among the different models of the UAV, the quadrotor has been extensively developed, researched, and applied over time. The notable quadrotor advantages are its flexibility, adaptivity, and ease of construction [
13]. The quadrotor is an aircraft with four rotors with associated propellers, which is capable of hovering, jerking, vertical takeoff and landing, and horizontal flight. Numerous quadrotors are being fabricated for academic research or commercial use, e.g., Pixhawk [
14], DraganFlyer X4 [
15], and DJI M300 [
16], and the boundaries of modeling theories [
17,
18,
19,
20] and control methods [
21,
22,
23,
24] are being advanced. Given that we mainly focused on UAV path planning rather than UAV control in this study, we did not consider the aspect of UAV control. However, several autopilot products or software [
25,
26,
27] cover the underlying control of UAVs, allowing researchers to perform and evaluate the designed planning methods on supported platforms.
Despite most UAVs being used in open and spacious outdoor situations rather than cramped and unpredictable indoor situations, demand has been growing for deploying UAVs indoors for specific missions, including manufacturing, inspection, and service [
28]. Unlike executing a flight outdoors, UAVs cannot use the global navigation satellite system (GNSS) as a location mechanism when indoors. As a result, indoor UAV localization systems typically use a visual camera [
29], laser [
30], wireless communication [
31], or motion capture systems [
32] as alternative techniques to assist with indoor tasks. Recently, systems based on new technology such as the Internet of Things (IoT) [
33], deep-learning-based monocular cameras [
34], and optimal mass flow sensors [
35] have been proposed. Additionally, some advanced systems have been developed using more conventional sensors providing solutions for indoor UAV applications, including camera-based tracking systems [
36], light detection and ranging (LiDAR)-based systems [
37], and multisensor fusion systems [
38].
To ensure the safety of UAV mission planning and autonomous flight, especially in indoor environments, UAV systems need to combine local environment awareness with global cognition. By creating a map of the indoor environment, the UAV can realize global cognition of the environment in which it is located, also providing the basis for a series of subsequent operations such as UAV path planning, mission configuration, and autonomous flight. Conversely, when relying solely on the UAV forming local perception of the surrounding environment, only emergency operations can be executed, such as obstacle avoidance, thus passively rather than actively ensuring safe UAV flights at the planning level. To allow UAVs to better understand indoor environments, a commonly used option is the application of payload sensors, where LiDAR provides benefits in illumination tolerance and object structure description. With a point cloud of the scenario as the only output, subsequent processes, such as environment modeling and path planning, can be performed. Based on this, numerous indoor UAV tasks can be accomplished, e.g., non-GPS navigation, interior inspection, and autonomous delivery.
The environmental awareness and cognition of a UAV enable UAV control at the planning level. To complete a UAV flight mission, the first step is deciding where to travel and stop, followed by controls to maintain proper movement during these tasks. Additionally, the UAV needs to be resilient to unforeseen circumstances, especially dynamic obstacles. The latter tasks were outside our scope in this study: our focus was on the process of creating a global traversal path for a UAV in an environment, i.e., path or route planning.
Environment modeling and path search are two major components of path planning. Many methods have been proposed by scholars in these fields, the most important of which are geometric, topological, and cell decomposition methods. The geometric method abstracts the elements of the environment using geometric shapes, such as a convex region combined with polynomial forms [
39]. Although these methods can intuitively describe the surroundings, their computational volume noticeably increases when the obstacles are dense and the layout is complicated; additionally, dealing with irregularly shaped obstacles is challenging. With the topological methods, the environment is abstracted as a graph structure, which considerably simplifies the environment and increases path search efficiency, but creating a topological graph is complicated and time-consuming. The core idea behind the cell decomposition method is to divide a large environment into small cells using a simple environment discretization method, which is easy to compute and applies well to situations with many obstacles and complex morphology, reducing the complexity of the environment model and increasing planning efficiency. The grid map [
40] is a typical cell decomposition method used in environment modeling.
The purpose of path search is to use specific algorithms to find a path in the environment so that the predetermined performance function returns an optimal value. According to the basic principle, path search algorithms can be divided into three types: traditional, sample-based, and simulation bionic methods.
Traditional methods were first proposed, but have since been enhanced. Dijkstra’s algorithm [
41], Floyd–Warshall algorithm [
42], A* [
43], D* [
44], and artificial potential field [
45] are a few examples. They are typically simple to calculate and easy to implement, which laid the foundation for resolving the path planning problem. Li et al. [
46] proposed a universal path planning method for UAVs that can solve the shortest safe path and a safe least-cost path. González et al. [
47] proposed an indoor path-planning algorithm for UAV-based contact inspection that can calculate a path in a few milliseconds. Xu et al. [
48] designed a resilient, enhanced algorithm for UAV 3D route planning based on the A* and artificial potential fields algorithms, overcoming the insufficient anti-disturbance ability of the traditional route planning algorithm.
Simulation bionic methods are inspired by natural entities or events, and they achieve their goal by simulating and grouping individual behaviors and interactions, providing a new possibility for solving complex problems. Typical methods include the genetic algorithm [
49], ant colony algorithm [
50], memetic algorithm [
51], etc. The simulation bionic methods are practical for UAV path planning. For example, Liu et al. [
52] designed a modified sparrow search algorithm and increased the efficiency in solving the UAV route planning problem. Wang et al. [
53] introduced a modified mayfly algorithm, which performed well in the UAV route planning problem. Li et al. [
54] combined cellular automata with the spanning tree algorithm to construct a route network in low-altitude airspace, providing a solution for the distribution of logistics UAV. However, although the concept of the simulation bionic methods can be intuitively understood, it has disadvantages in terms of the complexity of description and difficulty in modeling, which do not meet the time requirement and resource limitations of the onboard system.
Sample-based methods involve sampling subgoals in the configuration space to extend the search until the final goal is reached. Rapidly exploring random tree (RRT) [
55] and probabilistic roadmap (PRM) [
56] are two typical sample-based methods. RRT employs spatial sampling to determine the expansion direction of the search tree. This method can perform fast searches and is adaptable in high-dimensional space; however, it is not well-suited for environments with narrow spaces, and it does not guarantee an optimal path result. PRM, on the contrary, samples available spatial positions serving as nodes in a route network, from which a path search algorithm is used to solve an optimal path from beginning to end. This method converts the path search problem from an entire continuous space to a discrete graph with nodes and edges, making it applicable to path planning problems with high-dimensional and complex constraints. However, because this method is only probabilistically complete, the path result may not be optimal among all possible sample networks.
RRT is more suitable for exploring environments without prior information, whereas PRM is more suitable for selecting a better path in an environment with prior information, so is more suitable for applications that consider the safety of UAV flight. In 2004, Pettersson et al. [
57] used the PRM algorithm for an autonomous UAV. Methods based on PRM have been continuously proposed and tend to be combined with other methods. Chen et al. [
58] proposed an improved probabilistic roadmap with a potential field function for a quadrotor UAV. Mohanta et al. [
59] proposed a knowledge-based fuzzy-probabilistic roadmap for mobile robot navigation. Combining PRM with the A* algorithm is feasible [
60], and it works well with the ant colony algorithm [
61].
With the development of path planning methods, we have been constantly striving to increase operational effectiveness, reduce computing time, and maintain an optimal path result, to better meet the requirements of safe UAV flight. The sample-based method for path planning achieves an appropriate balance between effectiveness and efficiency. First, this method is well-suited for cell decomposition modeling, where the grid map is a common, mature, and easily used form to describe the environment. Second, as long as any interrelationship exists between cells in the map, it is capable of further simplifying the map by abstracting it into a graph composed of nodes and edges. Lastly, its path search shows high-quality performance in terms of computational efficiency and path result.
In this study, we focused on improving the computational efficiency of path planning, because it determines whether a UAV can complete the planning and execute an autonomous flight in real-time, i.e., in a few seconds. Due to the fact that indoor environments may be compact and complex, as well as sometimes dynamic and unpredictable, a UAV should be able to finish planning as quickly as possible to handle emergency situations. Based on a typical quadrotor model, we designed an indoor environment reduced-dimensional modeling method that employs point cloud projection to create a downscaled raster map of an indoor environment, reducing the indoor space from 3D to 2D while retaining necessary environmental information such as boundaries and obstacles. We used an adjacency relationship of the grids in a raster map to represent the spatial location relationship in 3D indoor space, thus markedly simplifying the environment. We combined several 2D maps into a multilayer map to produce an improved path-solving result in a complex environment where a single 2D map is not enough to effectively describe the actual situation. Furthermore, we developed an improved PRM planning method, which is an exploratory path search method that converts the path search in indoor environments into a graph search based on sampled nodes. Although the obtained paths may not be the shortest in length due to the sampling randomness, the search capability of the algorithm is remarkably improved, and solving for feasible paths in complex indoor environments is easier. The results of experiments showed that the proposed method substantially reduces the planning time compared with that of the basic PRM algorithm, and it performs well even on a resource-limited computing platform, whereas the postprocessing optimization of the generated paths further improves path quality to meet real-world requirements regarding the timely generation of autonomous UAV flight paths, thereby ensuring UAV flight safety.
2. Generation of Reduced-Dimensional Raster Map Based on Point Cloud Projection
A quadrotor UAV has flexible 3D mobility, i.e., loose constraints on vertical and horizonal motions, which considerably facilitates describing, representing, and modeling an environment. Therefore, we modeled an indoor environment by a point cloud projection method; then, we generated reduced-dimensional raster maps to represent various altitude ranges of the environment, based on which we designed and implemented an improved probabilistic roadmap planning method to obtain mission paths for the UAV. Additionally, we optimized the path by post-process to account for the efficiency and UAV flight safety. An overview of the method workflow is shown in
Figure 1.
2.1. Kinematic and Dynamic UAV Model Assumptions
A quadrotor UAV is composed of four rotors attached to the ends of four arms by a symmetric frame. As the direct power source of flight, the rotors can adjust each spinning speed to change the lift force generated by the attached propellers, allowing for flexible horizontal and vertical movements, constant motion, or relative stillness. The control system of a quadrotor is an underactuated system, with six degrees of freedom outputs (three translational motions and three rotational motions) controlled by only four inputs (the spinning speed of four rotors).
In this study, we selected the quadrotor as the assumed type of UAV in the modeling and planning. However, the actual type of the UAV was not our main concern as the current autopilot products and software provide good encapsulation and integration of underlying executions of the UAV, which do not require complex user control. The main reason why we used the quadrotor as the kinematic and dynamic model is that it is capable of flexible mobility in both the vertical and horizontal directions, especially hovering and jerking, which is highly automated by the autopilot.
Some assumptions are required to properly introduce the kinematic model of a quadrotor UAV. We assume that it has a symmetric and rigid structure, with propellers of equal height on the rotors, and the mass center is the same as the space center of the UAV.
We first define two coordinate systems: body inertial frame and fix inertial frame . The center is defined the same as the mass center of the UAV, with the forward and upward directions of the UAV being the x-direction and z-direction, respectively; the y-direction is determined by the right-hand rule. For simplicity, the fixed inertial frame has the same definition as the first body inertial frame of the UAV, and it does not change once determined.
As such, the UAV state
in the environment can be described as
where
denotes the position of the center of the quadrotor in a fixed frame, and
denotes the orientation of the quadrotor in the body frame represented in Euler angles (yaw, pitch, and roll), which can be further transformed to the fixed frame by
where
and
denote cos and sin operators, respectively.
To further simplify the dynamic model for ease of implementation, we overlook pitch and roll controls for now, because they strongly impact the flight stability of the UAV, and delegating these controls to the autopilot would be preferable. Translational and yaw controls are necessary, as the former is used to change the spatial position of the UAV, while the latter is used to adjust the heading direction. Thus, the following control states remain:
where
denotes the respective speeds with reference to the fixed frame, and
denotes the change rate of the yaw angle in the body frame.
These speed control parameters are inputs to the UAV kinematic model to keep the UAV on the resulting path solved at the planning level; they are also outputs of the UAV dynamic model, where traction and torque are inputs. However, because the implementation of dynamic modeling can be delegated to the autopilot and we focused more on planning methods than control methods for the UAV, we do not provide further discussion on this topic.
2.2. Indoor Environment Rasterization
In simple indoor environments, describing the inter-relationships of boundary surfaces and obstacle shapes is relatively simple, facilitating the vectorization of environmental elements. However, for complex indoor environments, the traditional vectorization method has limitations. For example, when a room is irregularly shaped, an increase in the number of walls causes the constraints of the boundary to become more complex, and more parameters must be added to the model to completely describe the entire environment, which also substantially affects the efficiency of modeling.
We implemented a downscaling modeling method for indoor environments based on point cloud projection that avoids the vectorization of environment elements and generates a reduced-dimensional raster map based on point cloud coordinate values. The method converts the original three-dimensional space to two-dimensional space and transforms the spatial location relationship between environment elements into the adjacency relationship between elements in the raster map, which considerably reduces the complexity of modeling, improves efficiency, and is more compatible.
The reduced-dimensional raster map consists of small elements called grids, each of which represents a specific size in space. They can be classified based on their values to distinguish boundaries, obstacles, and free space in the environment. Due to the fact that both the boundaries and obstacles are impassable on a map, they can be represented and grouped together as obstacle grids. In addition to obstacle grids, free grids exist in the map, which composes the entire set of map grids.
If we add an attribute and set a value of the free grid
and the obstacle grid
, we obtain a simple environment reduced-dimensional raster map, as shown in
Figure 2, which is essentially a binary image with a size of
.
2.3. Indoor Environment Point Cloud Projection
To preserve the relationship between obstacles and free space as much as possible throughout the conversion of a 3D point cloud to a 2D map, we adopt the indoor environment point cloud projection method, which projects the target 3D point cloud onto a parametric model. In this study, we projected the 3D point cloud of the indoor environment onto a horizontal plane along the vertical direction to provide a vertical view that serves as a reduced-dimensional raster map model of this indoor environment.
In addition, because the UAV has a limited field of vision and concentrates on a specific region rather than a global one, only the points within a range close to the UAV are projected. Thus, we further determine the range for projection according to the detection distance of the UAV:
where
,
,
,
,
, and
denote the projection range;
denotes the UAV position (or another specified center position of the focused point cloud);
denotes the detection range of the UAV and
denotes the specified range for altitude. All the variables are in the same local coordinates as the point cloud.
Any 3D point
in the point cloud satisfies
The conversion from 3D point
to 2D map grid
is as follows:
where
denotes the rounding sign to resample the 3D point to a 2D point and
denotes the map resolution scaling factor.
The reason why we chose a vertical projection is that indoor objects, in most cases, are vertically placed on the floor, and the free space also extends in the vertical direction. The vertical view is the most widely used map form in robot mapping and navigation applications, reflecting its usefulness, effectiveness, and representativeness.
However, the projection method may disregard the vertical structure of obstacles, particularly in complex environments. To overcome this issue, we further vary the
and
in the projection and construct grid maps representing the free space and obstacles at various altitudes. For example, a multilayer grid map
consists of grid maps at various altitudes, and the
ith map
is formed by the projection of point cloud
:
where
varies from
to
with a step size of
.
As a result, the UAV can search for a path not only in one single map but also by merging maps at various altitudes if necessary. In simple cases, a grid map of the near range of the UAV altitude is sufficient to solve a feasible path; in more complex cases, we first search for a path at the current altitudes, and if it is not feasible, we continue searching for subsequent paths in adjacent maps from where the initial search ended. As such, we achieve an appropriate balance between effectiveness and efficiency.
2.4. Indoor Environment Reduced-Dimensional Raster Map Generation
In the reduced-dimensional raster map of indoor environments, the map grid is divided into two categories: obstacle and free grids. The obstacle grids represent two types of environmental elements: boundaries and obstacles. Before constructing a map, the original point cloud of the indoor environment must be preprocessed to generate a usable map of the indoor environment.
Preprocessing commonly comprises the segmentation of floor and ceiling points, denoising, and other processes. Removal of the floor and ceiling points is necessary; otherwise, they obscure the location of the free space and cover the entire projection surface. We used random sample consensus (RANSAC) [
62] to segment and extract the floor and ceiling points. RANSAC not only satisfied our segmentation requirements, but also provided us with the parameters of the extracted planes that could be used to determine the UAV altitude in the environment. Based on this, we divide the space into varying altitudes and generate a map at each altitude.
The process of generating the reduced-dimensional raster map is shown in
Figure 3. More specifically, the procedure entails the following steps:
Extract the floor and ceiling points using point cloud segmentation, and remove them from the original point cloud. Segmentation range and height can be specified.
Calculate the maximum and minimum values of the remaining point clouds on the X and Y axes for the height and width of the map image, respectively. Scaling up of the image is optional to increase model accuracy.
Iteratively read the 3D position values of each point, and convert them into map grid coordinates by projection.
Repeat step 3 until all points have been traversed and obtain a binary image of the raster map.
Vary the specified height of projection to generate raster maps at various altitudes.
3. Improved Probabilistic Roadmap Planning for Safe UAV Flight
3.1. Basic PRM Algorithm
The PRM algorithm, which is essentially a graph-based path search method, is based on the fundamental concept of randomly generating sampling points in free space that serve as graph nodes. After verifying the connectivity of nodes and constructing a connection network, the PRM algorithm conducts a search and then solves a path from the source to the goal.
The PRM algorithm considerably simplifies the environment by discretizing the space into a graph, and is applicable to high-dimensional spaces with complex constraints. However, it is time-consuming and inefficient in network initialization. Additionally, its stability is restricted by the number of sampling nodes and their random locations. The algorithm is therefore probabilistically complete.
The workflow of the basic PRM algorithm mainly includes three parts: spatial sampling, edge generation, and path search. The pseudo-code for the basic PRM is shown in
Figure 4. More specifically, the procedure entails the following steps:
- (1)
Define a node set ; add the source node and the goal node .
- (2)
Generate a node
by random sampling in the entire map.
- (3)
Perform a collision check on . If it passes, add to ; otherwise, return to step 2.
- (4)
Repeat steps 2 and 3 until nodes in total have been generated, completing spatial sampling.
- (5)
Define an edge set .
- (6)
Traverse in and select other nodes to generate edge ; perform a collision check on it. If it passes, add it to .
- (7)
Repeat step 6 until all nodes have been traversed, completing edge generation.
- (8)
Define a graph and deploy a path search algorithm to solve the shortest path from to , completing the path search.
Figure 4.
Pseudocode of basic PRM.
Figure 4.
Pseudocode of basic PRM.
3.2. Improvement Strategies for PRM Algorithm
The basic PRM algorithm has disadvantages in terms of stability and efficiency.
Its insufficient stability is caused by its reliance on the number of sampling nodes and their random locations. When the number of randomly generated nodes in the space is small, or the distribution is unfavorably located, as shown in
Figure 5a,c, it may fail to form a network connecting the source and goal, instead generating several disconnected local networks. Nevertheless, the PRM algorithm is probabilistically complete, which means that as long as the random nodes are distributed throughout the space, a feasible path must be found. Therefore, the stability issue can be mitigated by appropriately increasing the number of nodes according to the complexity of the actual indoor environment.
The inefficiency is that some steps in the algorithm, particularly edge generation, are time-consuming. Each edge necessitates a collision check during generation to ensure a collision-free network. Furthermore, as the distance between nodes increases, the likelihood of obstacles between them increases, and generating a collision-free edge becomes more difficult. An effective solution is to reduce the number of collision checks and edge generations between distant nodes to improve the efficiency of the algorithm while having less impact on network connectivity.
To further reduce edge collision checks, we can adopt a strategy of constructing first and checking later, i.e., we do not perform the collision check on every pair of nodes in the process of edge generation after spatial sampling, but perform the collision check after solving a candidate path. Moreover, we eliminate the infeasible edges in the candidate path and find a new path that can reconnect the remaining edges. This strategy restricts the collision check of all edges to only the candidate path and its neighboring nodes and edges, therefore substantially lowering the number of collision checks and improving the efficiency of the algorithm.
3.3. Network Construction Based on Connection Distance
As the distance between nodes increases, the likelihood of obstacles between them increases, resulting in their invisibility and the impossibility of constructing collision-free edges. On the basis of this insight, we developed a method of network construction based on connection distance.
First, we set a “connection distance” parameter to determine whether to generate a connection edge between two nodes. During the edge generation process, the distance between each node is calculated when traversing each node to the other nodes. If it is above the threshold, the edge is not connected, and the subsequent collision check is skipped; otherwise, the collision check of the edge is performed again, and if it passes, a connected edge is generated between them.
The moderate connection distance is important. If the connection distance is too large, many colliding edges are still unnecessarily checked; however, if the connection distance is too small, network connectivity may be reduced or the network may become disconnected, which will affect the subsequent path search results, as shown in
Figure 6.
This method improves the efficiency of the algorithm with little impact on the network connectivity by reducing the connection of nodes whose distance exceeds an acceptable threshold. Comparative networks with different connection distances
are shown in
Figure 6, where the number of collision-free edges
and the number of colliding edges
are counted. As the connection distance increases, the number of colliding edges rapidly increases, while the number of collision-free edges slowly increases. This demonstrates that a proper connection distance can effectively reduce invalid checks for the colliding edges while assuring minimal disruption of network connectivity.
3.4. Path Local Check and Incremental Update
Based on the strategy of constructing first and checking later, we propose a method for path local checking and incremental updating.
After spatial sampling of the nodes, a network is constructed based on the connection distance, but no edge check is conducted at this stage. Hence, colliding edges may exist between the invisible nodes in the network, for which we then conduct a path search from the source to the goal for an initial path. On this path, we execute a minimum number of collision checks by incremental update. If an edge is collided, preventing direct passage between two nodes on the edge, we remove it from the network and search for a new path connecting the two nodes. These steps are repeated until all edges on the path pass the collision check, i.e., the entire path satisfies the no-collision requirement.
The workflow of the improved PRM algorithm mainly includes two parts: network initialization and path update. The pseudocode of the improved PRM is shown in
Figure 7. More specifically, the procedure entails the following steps:
- (1)
Define a node set ; add the source node and the goal node .
- (2)
Generate a node by random sampling in the entire map.
- (3)
Perform a collision check on . If it passes, add to ; otherwise, return to step 2.
- (4)
Repeat steps 2 and 3 until nodes in total have been generated.
- (5)
Define an edge set .
- (6)
Traverse in and select other nodes to generate edge ; add it to without performing collision checking.
- (7)
Repeat step 6 until all nodes have been traversed, completing network initialization.
- (8)
Define a graph and traverse a current node starting from .
- (9)
Find the nearest neighbor of and perform a collision check on . If it passes, add to result path and move backward to ; otherwise, remove from and update the network.
- (10)
Repeat step 9 until reaching , completing path update.
Figure 7.
Pseudocode of improved PRM.
Figure 7.
Pseudocode of improved PRM.
The methods of local path check and incremental update essentially comprise a path search strategy that reduces ineffective collision checks on edges, decreasing the time required and increasing algorithm efficiency. The method has strong applicability in environments that are not extremely complex, and a feasible path can be quickly solved with minimal redundancy in simple environments. The procedure of local check and incremental update is shown in
Figure 8. For colliding edges (red line) in the initial path, a new path (yellow lines) connecting two segments of the initial path is searched, which serves as a newly available local path for a final collision-free path (green lines).
3.5. Path Planning in Multilayer Grid Map
In more complex cases, a single map at a certain altitude might not be appropriate for solving a feasible path if obstacles are blocking the map and dividing it into several disconnected areas. Although areas in a single map may not be connected at the same altitude, they may be connected via another area at a different altitude. Therefore, we use a multilayer grid map for path planning.
Path search and update strategies in the multilayer map are quite similar to those in a single map; however, the essential distinction lies in how the transfer areas (overlapping areas of adjacent layers) are determined for the UAV to adjust its altitude.
To detect available transfer areas, we first use an image region-growing algorithm to identify and segment the disconnected areas in each single map. Due to the fact that the total number of the areas is uncertain, we randomly sample the growth seeds on the map. If the growing region contains a sufficient number of grids, we record it as a valid area and then continue to sample a new seed and search other areas until all valid areas have been segmented. Furthermore, we examine the connectivity between areas in each layer and those in the adjacent layers. If two areas have grids with the same X and Y coordinates, they are regarded as connected, and the overlapping area formed by the grids is considered to be a transfer area.
For the path search process, we attempt to find a path from the source to the goal in a single map at the default altitude. If the path search fails, meaning that impassible obstacles may be located at this altitude, we search in its adjacent layers for any area that overlaps the current search area. If several overlapping areas exist, we use a greedy strategy to select the area with the smallest horizontal distance from the goal as the next search area. In the selected overlapping area, we additionally sample a transfer node for the UAV adjusting its altitude, which also serves as a temporary goal node of the current search area and the source node of the next search area. Thus, we accomplish the cross-layer path search for UAVs in complex indoor environments.
The pseudo-code of path planning in the multilayer map is shown in
Figure 9. More specifically, the procedure entails the following steps:
Define as the currently used map (at altitude by default) and and as the source and goal for the current search, respectively; they are initialized in and at first.
- (1)
Define and initialize node set as the network nodes in .
- (2)
Start the search for a path from to on network .
- (3)
If the search fails, find another map that has the smallest distance with as the next map. Search the transfer area of the two maps and sample a transfer node in it, and set to . Start a new search in this configuration.
- (4)
If the search succeeds, record the path result in , switch the map to and to , and reset to .
- (5)
Repeat steps 4 to 5 until contains and .
Because our method is based on the pre-captured point cloud of the environment, the proposed method of map area detection considers a global perspective, i.e., with a priori knowledge of the environment. Possible enhancements for UAV discovery in an unknown environment were beyond the scope of this study.
Figure 9.
Pseudocode of path planning in multi-layer grid map.
Figure 9.
Pseudocode of path planning in multi-layer grid map.
5. Experimental Results
5.1. Source Data and Environment
The source data for the experiments in this study were 3D point cloud data of an indoor environment acquired using light detection and ranging (LiDAR) scanning equipment, including two indoor scenes whose details are listed in
Table 1.
Table 1.
Source data of indoor environment.
Table 1.
Source data of indoor environment.
Name | Description | No. Points | Data Quality | Overview |
---|
Scene 1 | Wuhan University library east reading room, 2nd Floor | 2,848,055 | locally vacant | Figure 13a |
Scene 2 | Underground parking lot | 6,794,787 | locally vacant | Figure 13b |
The map data we used in the path planning experiments included two reduced-dimensional raster maps of the aforementioned indoor environment and two virtual binary image maps [
63] used for comparison. The original point cloud data were missing some scans, which necessitated manual completion of the vacant areas to ensure the integrity of the maps before the subsequent operations. The details of the four indoor environment maps are listed in
Table 2, and
Figure 14 provides overviews.
The proposed indoor environment modeling method involves the processing of point clouds, and we implemented the associated experiments using C/C++ programming with the Point Cloud Library (PCL) [
64]. We also used the image processing library OpenCV to generate a reduced-dimensional raster map of the indoor environment.
The experimental simulation platform was MatLab, with an Intel® CoreTM i7-7700HQ 2.80GHz CPU and 8GB RAM. We interpreted a reduced-dimensional raster map of the indoor environment as a two-dimensional simulation space and then implemented the path planning algorithm in the same space.
To further simulate the condition of a typical UAV onboard system with limited resources, we validated and evaluated the performance of our methods using Manifold2-C, an onboard PC specially designed by DJI for their UAV products. The configuration was an Intel® CoreTM i7-8550U 1.80GHz CPU with 8G RAM. We manually limited its CPU usage down to 30%; otherwise, we found that it had a faster computation speed than in the previous experimental environment, as the CPU and RAM on Manifold2-C are more up-to-date and offer better performance under the same input power.
5.2. Evaluation Metrics
We evaluated the proposed methods using three metrics: pathfinding success rate, planning time, and path length.
Pathfinding success rate is the basic metric as it indicates the practicability of the path-planning method. If the improvement in the path-planning method results in a significant decrease in the pathfinding success rate compared with the original method, even if it achieves a considerable improvement in other aspects, such changes are meaningless because the algorithm no longer satisfies the most fundamental requirement of solving a path from the source to the goal.
We focused on planning time as a metric as some UAV autonomous flight applications involve collaboration between various onboard systems. If the path planning procedure is too slow, a series of subsequent operations will need to wait and will stagnate, which not only does not meet the real-time UAV positioning and planning requirements but is also detrimental to the safety of autonomous UAV flight.
Path length reflects the quality of the path as determined by the path planning method. The shorter the path length, the shorter the flight time, which can reduce unnecessary power consumption and help the UAV avoid energy shortages when performing autonomous flight missions, thereby enhancing flight safety.
Because our focus in this study was reducing the path planning time, it is worth noting that the algorithm tends to reach a solution faster when determining the path than when identifying the shortest path between the source and goal. On this basis, path postprocessing optimization is conducted to account for a non-shortest path length. As a result, the final path may be longer than the basic methods, but this is acceptable as long as the deviation is not excessive.
5.3. Experiments on Reduced-Dimensional Rasterization of Indoor Environment
In this study, we conducted experiments with real-world indoor scenes, including a library reading room and an underground parking lot. We performed the rasterization of the indoor environment based on the reduced-dimensional raster map generated by point cloud projection. The black grids represent impassable areas in the indoor environment, such as obstacles and boundaries, whereas the white grids represent passable and occupiable free space.
For simple environments, we projected the point cloud at the altitude midway between the floor and ceiling of the scene, within a 1 m height range. Moreover, we created a multilayer grid map to test our planning method in a more complex scenario where the distribution of obstacles varied among the different altitudes of the environment. We had no existing source data that met our needs, so we manually created a multilayer map by editing obstacles in the map that divided the maps into several areas. Different layers of the multilayer grid map are shown in
Figure 15, representing the reduced-dimensional maps of the environment at different altitudes. We assumed that the altitude of Layer 1 was lower than that of Layer 2. On this particular map, if a UAV wanted to move from Area 1 to Area 2, it had to execute the following flight:
- (1)
Start from somewhere in Area 1 at the altitude of Layer 1.
- (2)
Move to the overlapping area of Areas 1 and 3.
- (3)
Ascend to the altitude of Layer 2.
- (4)
Move to the overlapping area of Areas 3 and 2.
- (5)
Descend to the altitude of Layer 1.
- (6)
Continue the flight in Area 2 at the altitude of Layer 1.
The map of the library reading room in
Figure 14c shows that a portion of the obstacle areas representing the library cabinets was broken. This was due to missing scans in the original point cloud data, which we resolved by recollecting higher-quality indoor space point cloud data. The obstacles near the wall were the projections of desks and chairs. Although some space between them and the ceiling in the actual indoor space was free, this kind of space accounted for a small portion of the total space and had no substantial impact on the connectivity of the free space, so the waste of this portion of the space was still acceptable.
The map of the underground parking lot in
Figure 14d shows that vehicles in the parking lot did not notably interfere with the point cloud projection because we specified the projection method that extracts the height of the upper middle region of the parking lot.
Using the reduced-dimensional rasterization of the indoor environment considerably simplified the environment and met the data requirements of the subsequent path-planning experiments.
Table 3 lists a comparison of the data before and after modeling of the two indoor scenes in this experiment, demonstrating that the reduced-dimensional modeling substantially reduced the data volume. The final maps generated by the method proposed in this study were essentially images, and their spatial accuracy was freely adjustable, and the corresponding data size changed with the image resolution.
5.4. Experiments on Network Construction Based on Connection Distance
The purpose of setting the connection distance parameter in network construction is to avoid collision checks between distant nodes, because connections that span a larger area are more likely to intersect with obstacles in the environment.
In the experiment, we defined the connection distance
as follows:
where
and
denote the size of the grid map, and
denotes the scale factor, i.e., connection distance weight.
Using Map_lib and Map_pkl data, we separately set
to 0.25, 0.5, 0.75, and 1, i.e., the connection distance was 1/4, 1/2, 3/4, and 1 times the length of the map diagonal, respectively. For different numbers of nodes, we recorded the number of connected edges and network construction time, as well as the path length obtained by path search based on this network. The experimental results are listed in
Table A1.
The network construction time and path length for the connection distance experiments are shown in
Figure 16. With smaller connection distances (
= 0.25), the number of constructed network edges was smaller and the construction time was shorter, but this resulted in a less successful path search and a longer path.
As the connection distance weight increased, the network construction time accordingly increased, and the path length obtained from the path search tended to be shorter as a result of the increased number of possible connecting edges. However, the growth in the number of collision-free edges and the decrease in path length tended to be flat, and the number of colliding edges markedly increased. These redundant checks also resulted in a larger waste of network construction time, confirming the hypothesis that increasing distance decreases the possibility of collision-free edges. In the process of network construction, the algorithm performance could be enhanced by selecting a moderate connection distance.
5.5. Experiments on Improved Probabilistic Roadmap Planning
In this study, we used the four raster maps shown in
Figure 14 to conduct probabilistic roadmap planning experiments. For each map, we positioned the source and goal near the diagonal position of the map, varied the number of nodes and connection distance, and repeated the experiment to record the pathfinding success rate, planning time, and path length of the basic and improved PRM methods.
The path planning results of the four maps are shown in
Figure 17, where blue dots represent network nodes; blue and red lines represent visible and nonvisible edges, respectively; yellow lines represent updated edges during path search; cyan lines represent the forward-checked optimal path; and green lines represent the backward-checked optimal path, i.e., the final path result.
Comparing the result of the basic PRM with that of the improved PRM, we found two common cases. In the first case, the majority of nodes in both paths were the same but had slightly different path shapes; in the second case, the two paths had considerably different routes because we adopted an incremental update strategy and the path search followed the rule of greedy extension rather than that of global length shortening. Notably, as a result of our path optimization, the path length of our method was often comparable to that of the basic one, despite the route difference.
The path planning results of the multilayer grid map are shown in
Figure 18. The source and the goal were the same as in Map_lib, with the source located in Area 1 and the goal in Area 2 (as shown in
Figure 15). To travel from start to end, the UAV adjusted its flight altitude, i.e., ascending in the overlapping of Areas 1 and 3 and descending in the overlapping of Areas 3 and 2. The complete path from start to end was composed of three subpaths connected by two transfer nodes where the UAV performed vertical movements.
We repeated the experiments by configuring different connection distances for a different number of nodes. We recorded the planning time and path length of the basic and improved PRM methods. The comparative results of Map1 and Map2 are listed in
Table A2. The basic PRM spent most of its time constructing the network, whereas the improved PRM spent most of its time on path search, network update, and path postprocessing optimization, as the check of network connectivity was deferred.
For Map1 and Map2, we calculated the average planning time and average path length ratio before and after the improvement, as shown in
Figure 19. The planning time of the improved PRM was only approximately 30% of that of the basic PRM, resulting in a substantial reduction in path planning time. Due to some strategies adopted by the algorithm, it tended to find a path as quickly as possible rather than determine the shortest path between the source and the goal; consequently, the path length was longer than that of the basic PRM by less than 10%, which is acceptable given the considerable increase in planning time. In addition, the planning time and path length showed that as the number of nodes increased, the advantage in the planning time of the proposed method became more apparent.
We also conducted the same experiments for two reduced dimensional raster maps of indoor environments, Map_lib and Map_pkl; the results are listed in
Table A3. From a comparison of the results of the basic and improved PRM on Map_lib and Map_pkl, as shown in
Figure 20, our conclusions were basically the same: the improved PRM provided an advantage over the basic PRM in terms of planning time, at the cost of an increase in path length, which was acceptable.
Comparing the binary image map and the reduced-dimensional raster map of the indoor environment, we found that for the simple maps (Map1 and Map_pkl), the planning time stability in the improved PRM was high, i.e., the planning time did not notably fluctuate with changes in the number of nodes or the connection distance. For the complex maps (Map2 and Map_lib), the stability decreased, but was still considerably better than that of the basic PRM.
We also conducted experiments on an onboard PC to simulate the integration of our planning method into an autonomous UAV system. We tested our improved PRM method on the onboard PC and evaluated the planning time using the same input data as the original experiments. At first, we did not set a resource limit on the onboard PC, but due to its hardware configuration being more up-to-date than that of our desktop PC, it performed even better. Therefore, we manually limited the CPU usage down to 30% to more accurately simulate a resource-limited configuration.
The experimental results of the improved PRM on Map_lib and Map_pkl on the onboard PC (with CPU usage limited to 30%) are listed in
Table A4, and they are shown in
Figure 21. The planning times in both experimental environments exhibited comparable trends under the same input data. Additionally, the consumed time was fundamentally influenced by the hardware configuration, whereas our planning method maintained appropriate performance despite resource limitations. Moreover, we showed that the current onboard hardware was capable of high-level configurations (except for those dedicated to micro vehicles), so scholars can more easily deploy and test their methods on onboard computing platforms with high performance.
5.6. Experiments on Path Postprocessing Optimization
Using the same reduced-dimensional raster maps of the indoor environment, we conducted the experiments of path post-processing optimization. Experimental results are shown in
Figure 22, where thick yellow lines represent updated edges, yellow lines represent collision-free path after path search, cyan lines represent the backward-checked optimal path, and green line represents the forward-checked optimal path, i.e., the final path result.
In Map_lib and Map_pkl, the paths were solved using the basic and improved PRM methods for comparison. The initially obtained collision-free paths were then optimized using two-step path postprocessing. The experimental results are listed in
Table A5.
From the path postprocessing optimization results shown in
Figure 23, we found that the proposed optimization method substantially improves the path quality for the initially obtained paths, with longer lengths and higher path repetition rates in the improved PRM, as the method minimized redundant nodes and allowed the path to attain a “straightened” route. This path postprocessing optimization method solves the problem where the initial path quality obtained by the improved PRM method is inferior to that of the basic one, completing the proposed path planning scheme. As a result, the optimization method avoids redundant motions and ensures a collision-free and direct path for the UAV, which is conducive to the safety of autonomous flight in indoor environments.
6. Discussion
In this study, we primarily focused on modeling an indoor environment and improving the PRM path-planning method. We assumed the UAV was a quadrotor model and reduced the controls to 3D translation and rotation in yaw angle. This assumption is relatively simple but was sufficient for the purposes of this study, as numerous flight control products and software have already encapsulated and integrated UAV operations into simple commands. More in-depth research can be conducted on the topic of UAV control.
The data source for indoor environment modeling was a point cloud. Furthermore, we used a point cloud projection scheme to generate reduced-dimensional raster maps of indoor environments. Although this method preserves the semantic understanding of indoor environment elements and the modeling speed is faster, the problem of noise points present in the point cloud must still be solved, as determining whether these noise points represent tiny obstacles or actually are noise points is crucial to the safety of indoor UAV flights. In the actual process of map generation, we must also be problem-specific because the presence of too many noise points will impede the efficiency of solving the path, and eliminating these noise points may pose a safety risk, so we should strike a balance between these two factors.
Considering the complexity of indoor environments, we generated grid maps at various altitudes and constructed a multilayer map. This method increases the robustness of path search and the applicability of the UAV.
The proposed improved PRM planning method aims to solve the computational efficiency problem caused by the basic PRM while minimizing the impact on the path length. The results of our experiments showed that the proposed method is effective. However, the efficiency of the proposed method may decrease in overly complex indoor situations, because if collision checks on edges are not performed when constructing the original network, a large number of edge adjacency information updates are required in the subsequent search and update process; each update necessitates at least one local path search, resulting in a substantial decrease in efficiency. To avoid repeated checks, it is recommended to check the connection between all nodes at the beginning.
The key to our improvement provided by our strategy is reducing a large number of collision checks in the basic method, because collision checks performed during network construction may be meaningless for two reasons: First, as the distance between nodes increases, the possibility of visibility decreases, because more obstacles created blockages between them. Second, the farther nodes are from the source and goal nodes, the less likely they are to become candidates, so checks on them are often unnecessary in the end. As a result, we adopted the strategy of constructing first and checking later to eliminate as many unnecessary checks as possible and searched for paths based on the overall effectiveness of the candidate nodes from high to low, which can more quickly solve the paths while retaining the ability to search for all nodes because, in extreme cases after traversing through all nodes in the space, as long as a path solution exists, the path solution should be obtained.