37,730
Views
4
CrossRef citations to date
0
Altmetric
Articles

A survey on vision-based UAV navigation

, , ORCID Icon & ORCID Icon
Pages 21-32 | Received 28 May 2017, Accepted 11 Dec 2017, Published online: 12 Jan 2018

Abstract

Research on unmanned aerial vehicles (UAV) has been increasingly popular in the past decades, and UAVs have been widely used in industrial inspection, remote sensing for mapping & surveying, rescuing, and so on. Nevertheless, the limited autonomous navigation capability severely hampers the application of UAVs in complex environments, such as GPS-denied areas. Previously, researchers mainly focused on the use of laser or radar sensors for UAV navigation. With the rapid development of computer vision, vision-based methods, which utilize cheaper and more flexible visual sensors, have shown great advantages in the field of UAV navigation. The purpose of this article is to present a comprehensive literature review of the vision-based methods for UAV navigation. Specifically on visual localization and mapping, obstacle avoidance and path planning, which compose the essential parts of visual navigation. Furthermore, throughout this article, we will have an insight into the prospect of the UAV navigation and the challenges to be faced.

1. Introduction

An unmanned aerial vehicle (UAV) is an aircraft which can fly without a human pilot aboard. Nowadays, more and more UAVs are recruited for civilian applications because of its high mobility and flexibility. However, in some complex environments, the UAV cannot precisely perceive the surrounding environment and act properly due to the limitations of communication and perception ability of traditional sensors. Although a lot of effort has been spent on overcoming these weaknesses, a more efficient and effective method still needs to be developed. Therefore, the high-performance autonomous navigation capability is of great significance for the development and application of UAVs.

1.1. UAV navigation

UAV navigation can be seen as a process that robots make a plan on how to safely and quickly reach the target location, which mostly relies on current environment and location. In order to successfully complete the scheduled mission, a UAV must be fully aware of its states, including location, navigation speed, heading direction as well as starting point and target location. To date, various navigation methods have been proposed and they can be mainly divided into three categories: inertial navigation, satellite navigation, and vision-based navigation. Nevertheless, none of these methods is perfect; therefore, it is crucial to adopt an appropriate one for UAV navigation according to the specific task. The vision-based navigation proves to be a primary and promising research direction of autonomous navigation with the rapid development of computer vision. First, the visual sensors can provide abundant online information of the surroundings; second, visual sensors are highly appropriate for perception of dynamic environment because of their remarkable anti-interference ability; third, most of visual sensors are passive sensors, which also prevent the sensing system from being detected. Europe and the United States have already established research institutions, such as NASA Johnson Space Centers (Herwitz et al. Citation2004). MIT (Langelaan and Roy Citation2009), University of Pennsylvania (How et al. Citation2008) and many other top universities are also vigorously developing research on vision-based UAV navigation and have incorporated this technology into next generation air transport systems, such as NextGen (Strohmeier et al. Citation2014) and SESAR (Hrabar Citation2008).

The complete illustration of vision-based UAV navigation is shown as Figure .

Figure 1. Vision-based UAV navigation.

Figure 1. Vision-based UAV navigation.

With inputs from exteroceptive and proprioceptive sensors, after internal processing of localization and mapping, obstacle avoidance and path planning, the navigation system will finally output continuous control to drive the UAV to the target location.

1.2. UAV sensing

Normally, UAVs obtain states of their own and information of surroundings from both exteroceptive and proprioceptive sensors. The traditional sensors used for navigation are mainly GPS, axis accelerometer, gyroscope, and inertial navigation system (INS). However, subjected to the operating principle, they are prone to affect the performance of navigation and localization. On one hand, one of the great drawbacks of GPS is its reliability, whose localization accuracy is positive correlation to the number of available satellites (Araar and Aouf Citation2014). On the other hand, due to the propagation of bias error caused by the integral drift problem, INS would result in loss of accuracy to some extent. Meanwhile, small errors of acceleration and angular velocity are continuously incorporated into the linear and quadratic errors of velocity and position, respectively.

More or less, the defects of traditional sensors constraint the UAV in both production and life applications. Therefore, researchers are being more concerned about the use of novel methods to enhance both the accuracy and robustness of UAV’s state estimation. Ideally, we can obtain better pose estimation by multiple sensor data fusion (Carrillo et al. Citation2012), which incorporates advantages of different types of sensors. Nonetheless, limited to the specific environment (for example, GPS-denied area) and payload of the UAV, it is assumed to be unnecessary and impractical for some small UAVs with multiple sensors. Therefore, a more general approach is expected to enhance the UAV’s environmental perception ability.

Visual navigation is using visual sensors. Comparing to the GPS, laser lightning, ultrasonic sensors, and other traditional sensors, visual sensors can acquire rich information of surroundings, involving color, texture, and other visual information. Meanwhile, they are cheaper and easier to deploy, so vision-based navigation has becoming a hot spot in the field of research. As shown in Figure , visual sensors typically include the followings: (a) monocular cameras, (b) stereo cameras, (c) RGB-D cameras, and (d) fisheye cameras.

Figure 2. Typical visual sensors. (a) monocular cameras, (b) stereo cameras, (c) RGB-D cameras, (d) fisheye cameras.

Figure 2. Typical visual sensors. (a) monocular cameras, (b) stereo cameras, (c) RGB-D cameras, (d) fisheye cameras.

Monocular cameras are especially suited for applications where compactness and minimum weight are critical, in addition to that, lower price and flexible deployment make them a good option for UAVs. However, monocular cameras are not able to obtain depth map (Rogers and Graham Citation1979). A stereo camera is actually a pair of the same monocular cameras mounted on a rig, which means that it provides not only everything that a single camera can offer but also something extra that benefits from two views. Most importantly, it can estimate depth map based on the parallax principle other than the aid of infrared sensors (Seitz et al. Citation2006). RGB-D cameras can simultaneously obtain depth map and visible image with the aid of infrared sensors, but they are commonly used in indoor environment due to the limited range. Fisheye cameras are a variant of monocular cameras which provide wide viewing angle and are attractive for obstacle avoidance in complex environments, such as narrow and crowded space (Matsumoto et al. Citation1999; Gaspar, Winters, and Santos-Victor Citation2000).

The rest of the paper is organized as follows: First, in Section 2, we introduce three different kinds of visual localization and mapping methods. Next, in Section 3, we provide a review on the obstacle detection and avoidance technique in autonomous flight. Then, in Section 4, we focus on the path and trajectory planning approaches. Finally, in Section 5, we make a conclusion, together with further discussion on specific challenges and future trends of vision-based UAV navigation.

2. Visual localization and mapping

Considering the environment and prior information used in navigation, visual localization, and mapping systems can be roughly classified into three categories: mapless system, map-based system, and map-building system (Desouza and Kak Citation2002) (Figure ).

Figure 3. Visual localization and mapping systems.

Figure 3. Visual localization and mapping systems.

2.1. Mapless system

Mapless system performs navigation without a known map, and UAVs navigate only by extracting distinct features in the environment that has been observed. Currently, the most commonly used methods in mapless system are optical flow methods and feature tracking methods.

Generally, we can divide the optical flow techniques into two categories: global methods (Horn and Schunck Citation1981) and local methods (Lucas and Kanade Citation1981). As early as 1993, Santos-Victor et al. (Citation1993) invented a method imitating the bee’s flight behavior by estimating the object movement through cameras on both sides of a robot. First, it calculates the optical velocity of two cameras relative to the wall, respectively. If they are same, the robot moves along the central line; otherwise, the robot moves along the speed of small places forward. However, it is prone to have a poor performance when navigating in texture-less environment. Since then, we have witnessed great development of optical flow approaches and also made several breakthroughs in detection and tracking fields. Recently, a novel approach has been proposed for scene change detection and description using optical flow (Nourani-Vatani et al. Citation2014). Moreover, by incorporating inertial measurement unit (IMU) with the optical flow measurements (Herissé et al. Citation2012), researchers have achieved hovering flight and landing maneuvre on a moving platform. With dense optical flow calculation, it can even detect movements of all moving objects (Maier and Humenberger Citation2013), which plays an important role in high level tasks, such as surveillance and tracking shooting.

The feature tracking method has become a robust and standard approach for localization and mapping. It primarily tracks invariant features of moving elements, including lines, corners, and so on and determines the movement of an object by detecting the features and their relative movement in sequential images (Cho et al. Citation2013). During the process of robot navigation, invariant features that have been previously observed in the environment are likely to be reobserved from different perspectives, distances, and different illumination conditions (Szenher Citation2008). They are highly suitable for navigation. Traditionally, natural features used in localization and mapping are not dense enough to avoid obstacles. Li and Yang (Citation2003) proposed a behavioral navigation method, which utilized a robust visual landmark recognition system combining with a fuzzy-based obstacle avoidance system for obstacle avoidance.

2.2. Map-based system

Map-based system predefines the spatial layout of environment in a map, which enables the UAV to navigate with detour behavior and movement planning ability. Generally, there are two types of maps: octree maps and occupancy grids maps. Different types of maps may contain varying degrees of detail, from the 3D model of complete environment to the interconnection of environmental elements.

Fournier, Ricard, and Laurendeau (Citation2007) used a 3D volumetric sensor to efficiently map and explore urban environments with an autonomous robotic platform. The 3D model of the environment is constructed using a multi-resolution octree. Hornung et al. (Citation2013) developed an open source framework for representation of 3D environment models. The main idea here is to represent the model using octree, not only the occupied space, but also the free and unknown space. Furthermore, the 3D model is compacted using an octree map compression method, which allows the system to efficiently store and update the 3D models.

Gutmann, Fukuchi, and Fujita (Citation2008) used stereo vision sensor to collect and process data, which can then be used to generate a 3D environment map. The core of the method is an extended scan line grouping approach to precisely segment the range data into planar segments, which can effectively deal with the data noise generated by the stereo vision algorithm when estimating depth. Dryanovski, Morris, and Xiao (Citation2010) used a multi-volume occupancy grid to represent 3D environments, which explicitly stores information about both obstacles and free space. It also allows us to correct previous potentially erroneous sensor readings by incrementally filtering and fusing in new positive or negative sensor information.

2.3. Map-building system

Sometimes, due to environmental constraints, it is difficult to navigate with a preexisting accurate map of the environment. Moreover, in some emergent cases (such as disaster relief), it would be impractical to obtain a map of the target area in advance. Thereby under such circumstances, building maps at the same time as flight would be a more attractive and efficient solution.

Map-building system has been widely used in both autonomous and semi-autonomous fields, and is becoming more and more popular with the rapid development of visual simultaneous localization and mapping (visual SLAM) techniques (Strasdat, Montiel, and Davison Citation2012; Aulinas et al. Citation2008). Nowadays, UAVs are getting much smaller than before, which limits their payload capacity to certain extents. Therefore, researchers have been showing more interest in the usage of simple (single and multiple) cameras rather than the traditional complex laser radar and sonar, etc.

One of the earliest attempts at the map-building technique using a single camera was carried out by the Stanford CART Robot (Moravec Citation1983). Subsequently, an interest operator algorithm was improved to detect 3D coordinates of images. The system basically demonstrated 3D coordinates of objects, which were stored on a grid with 2 m cells. Although this technology can reconstruct the obstacles in the environment, it is still incapable of modeling large-scale world environment.

After that, under the goal of simultaneously recovering poses of cameras and structure of the environment, vision-based SLAM algorithms, which are based on cameras, have made considerable progress, and derived three types of methods: indirect method, direct method, and hybrid method, according to its way of visual sensor image processing.

2.3.1. Indirect method

Instead of using images directly, the indirect method firstly detects and extracts features from images, and then takes them as inputs for motion estimation and localization procedures. Typically, features are expected to be invariant to rotation and viewpoint changes, as well as robust to motion blur and noise. For the last three decades, a comprehensive study of feature detection and description has been undertaken and there have been various types of feature detectors and descriptors (Li and Allinson Citation2008; Tuytelaars and Mikolajczyk Citation2008). Hence, current SLAM algorithms are mostly under the feature-based framework.

Davison (Citation2003) presented a top-down Bayesian framework for single camera localization with real-time performance via mapping a sparse set of natural features. It is a milestone for monocular visual SLAM and has a great impact on future work. Klein and Murray (Citation2007) proposed a parallel tracking and mapping algorithm, which is the first one to divide the SLAM system into two parallel independent threads: tracking and mapping. This has almost been the standard of modern feature-based SLAM system. Mahon et al. (Citation2008) proposed a novel approach for large-scale navigation. Visual loop-closure detections are used to correct the drifts of trajectories which are common in long-term and large-scale environment. Celik et al. (Citation2009) presented a visual SLAM-based system for indoor environment navigation, where the layout is unknown and without the aids of GPS. UAVs are only equipped with a single camera to estimate the state and range. The core of the navigation strategy is to represent the environment via energy-based feature points and straight architectural lines. Harmat, Trentini, and Sharf (Citation2015) proposed a visual attitude estimation system for multiple cameras based on multi-camera parallel tracking and mapping (PTAM) (Klein and Murray Citation2007). It combines the ego motion estimation from multiple cameras, and parallelizes the pose estimation and mapping modules. The authors also proposed a novel external parametric calibration for cameras with non-overlapping fields of view using multiple cameras.

However, most of the indirect methods extract only distinct feature points from images, which can at most reconstruct a specific set of points (traditionally, corners). We call this kind of methods sparse indirect method, which can only reconstruct a sparse scene map. So currently, researchers have been looking forward to the dense indirect methods that can reconstruct dense maps. Valgaerts et al. (Citation2012) used a dense energy-based method to estimate the fundamental matrix and find dense correspondences from it. Ranftl et al. (Citation2016) produced a dense depth map from two consecutive frames using segmented optical flow field, which means that the scene can be reconstructed densely under this framework by optimizing a convex program.

2.3.2. Direct method

Though indirect methods prove to perform well in ordinary environment, they are prone to get stuck in texture-less environment. So, direct methods also become a hot spot in the last decade. Different from indirect methods, direct method optimizes geometry parameters using all the intensity information in the image, which can provide robustness to photometric and geometric distortions present in images. Apart from that, direct methods usually find dense correspondences, so it can reconstruct a dense map at an extra cost of computation.

Silveira, Malis, and Rives (Citation2008) proposed a novel method for camera poses and scene structure estimation. It directly uses image intensities as observations, utilizing all information available in images, which is more robust than indirect methods in the environment with little feature points. Newcombe, Lovegrove, and Davison (Citation2011) presented a real-time monocular SLAM algorithm, DTAM, which also estimates the camera’s 6DOF motion using direct methods. By frame-rating the whole image alignment, it can generate dense surfaces at frame rate based on the estimated detailed textured depth maps with current commodity GPU hardware. Engel, Schöps, and Cremers (Citation2014) employed an efficient probabilistic direct approach to estimate semi-dense maps, which can then be used for image alignment. Different from methods that optimize parameters without scale, LSD SLAM (Engel, Schöps, and Cremers Citation2014) uses a pose graph optimization over Sim(3) (Kümmerle et al. Citation2011), which explicitly takes scale factor into account, allowing for scale drift correction and loop closure detection in real time.

2.3.3. Hybrid method

Hybrid method combines the direct and indirect methods together. First, it initializes feature correspondences using indirect methods, and then continuously refines camera poses by direct methods, which is faster and more accurate.

Forster, Pizzoli, and Scaramuzza (Citation2014) innovatively proposed a semi-direct algorithm, SVO, to estimate the state of a UAV. Similar to PTAM, motion estimation and point cloud mapping are implemented in two threads. For motion estimation, a more accurate motion estimation is obtained by directly using the pixel brightness and gradient information, and combining with the alignment of the feature points and minimization of the reprojection error. Then, Forster et al. (Citation2015) carried out a computationally efficient system for real-time 3D reconstruction and landing-spot detection for UAVs, in which only smartphone processors are used as the processing unit. Different from PTAM, in order to achieve real-time performance, SVO needs to run with a high frame rate camera. It was designed mainly for onboard applications which have limited computation resources.

2.3.4. Multi-sensor fusion

Since laser scanners can easily access 3D point clouds with relatively good quality, they are very popular in ground mobile robots (Bonin-Font, Ortiz, and Oliver Citation2008). And with its size getting smaller, more UAVs can also equip with laser scanners. This enables a fusion of different types of measurements from different kinds of sensors. Benefiting from the timeliness and complementarity of multi-sensor, the fusion of multi-sensor enables more accurate and robust estimation of state of a UAV.

Lynen et al. (Citation2013) presented a general purpose multi-sensor fusion extended Kalman filter (MSF-EKF) that can handle different types of delayed measurement signals from multiple sensors, and provides a more accurate attitude estimation for UAV control and navigation. Magree and Johnson (Citation2014) proposed an integrated navigation system, which combines both visual SLAM and laser SLAM with an EKF-based inertial navigation system. The monocular visual SLAM finds data association and estimates the state of UAVs, while the laser SLAM system performs scan-to-map matching under a Monte Carlo framework.

3. Obstacle detection and avoidance

Obstacle avoidance is an indispensable module of autonomous navigation, since it can detect, provide essential information of nearby obstacles, and reduce risks of collision as well as pilots’ operation errors. So, it can greatly increase the autonomy of UAVs.

The basic principle of obstacle avoidance is to detect obstacles and figure out the distances between the UAV and obstacles. When an obstacle is getting closer, the UAV is supposed to avoid or turn around under the instructions of obstacle avoidance module. One of the solutions is to measure distance using range finders, such as radar, ultrasonic, and IR, etc. Nevertheless, they are incapable of getting enough information in complex environment due to their limited field of view and measurement range. Compared to those issues, visual sensors can get abundant visual information, which can be processed and used for obstacle avoidance.

There are mainly two kinds of methods for obstacles avoidance: optical flow-based methods and SLAM-based methods. Gosiewski, Ciesluk, and Ambroziak (Citation2011) avoided the obstacles by means of image processing. Based on optical flow, it is able to generate local information flow and obtain image’s depth. Al-Kaff et al. (Citation2016) detected the change of obstacle size during flight. This method simulates the mechanism of the human eyes that objects in the field of view are getting bigger as you are closer. Based on this principle, it can detect the obstacle by comparing the sequential images, and find out whether the obstacle is getting closer.

A variety of bionic insect vision optical flow navigation methods have also been proposed. Inspired by bees’ vision, (Srinivasan and Gregory Citation1992) proposed a simple non-iterative optical flow method for measuring the global optical flow and self-motion of the system. As a basic local motion detection unit, the Reichardt model (Haag, Denk, and Borst Citation2004) is inspired by the visual nerve structure of insects. Ruffier et al. (Citation2003) designed the flow strategy and the sensor based on the compound structure of flies. These are the insect vision algorithms used in UAVs to apply theoretical validation. Recently, inspired by insect vision (Bertrand, Lindemann, and Egelhaaf Citation2015), a physics student Darius Merk proposed a method that judges the distance between objects only by the speed of light (https://techxplore.com/news/2016-07-drone-obstacles-insect.html#nRlv). It is simple but efficient, because lots of insects in nature can detect the surrounding obstacles by light intensity. During the flight, their image motion on the retina produces light flow signal, this optical flow for the insect visual navigation provides wealthy information of spatial characteristics. So, insects can quickly figure out whether the obstacles can be passed safely, according to the intensity of the light passing through the leaf gap.

However, optical flow-based method cannot acquire precise distance, which may limit the usage in some specific missions. By contrast, SLAM-based methods can provide precise metric maps with a sophisticated SLAM algorithm, so UAVs can navigate and avoid obstacles with more environment information (Gageik, Benz, and Montenegro Citation2015).

Moreno-Armendáriz and Calvo (Citation2014) presented a method of mapping previously unknown environment by a SLAM system. And meanwhile, a novel artificial potential field method is utilized to avoid both static and dynamic obstacles. Bai et al. (Citation2015) proposed a generating mechanism of self-adaptive map feature points, which is based on the PTAM algorithm, to deal with the poor illumination of indoor environment and the dependency on number of feature points. And it proves to be effective with real-time performance in GPS-denied environments. Esrafilian and Taghirad (Citation2016) put forward a method based on oriented fast and rotated brief SLAM (ORB-SLAM). First, it processes video data, by computing 3D locations of the UAV and generating a sparse point cloud map. Then, it enriches the spare map to more dense. Finally, it can generate a collision-free road map by applying potential field method and quickly exploring the random tree (RRT).

4. Path planning

Path planning is an important task in the UAV navigation, it means finding an optimal path from the starting point to the target point, based on some performance indicators (such as the minimum cost of work, the shortest flying time, the shortest flying route). And during this process, the UAV needs to avoid obstacles. According to the type of environment information utilized to compute an optimal path, this problem can be divided into two types: global path planning and local path planning. Global path planning aims to find an optimal path based on a priori global geographical map. However, global path planning is not enough to control a UAV in real time, especially when there are some other tasks to be done immediately or unexpected obstacles appearing during the flight. Therefore, the local path planning is in need so that it constantly acquires sensors’ information from surrounding environment, and computes the collision-free path in real time. An illustration of the two path planning methods is shown as Figure .

Figure 4. Global and local path planning.

Figure 4. Global and local path planning.

4.1. Global path planning

Global path planner requires the start and target locations within a constructed map to calculate an initial path, so the global map is also called a static map. The commonly used algorithms for global path planning include heuristic searching methods and a series of intelligent algorithms.

4.1.1. Heuristic searching methods

A-star algorithm is a typical heuristic search method, which evolved from the classic Dijkstra algorithm. In recent years, the A-star algorithm has been greatly developed and derived lots of other improved heuristic search methods. Vachtsevanos et al. (Citation1997) used an orographic database to build a digital map and used a modified A-star algorithm to search for the best track. Rouse (Citation1989) divided the whole region into several square grids, and used the heuristic A-star algorithm to achieve optimal path planning, which is based on the value function of different grid points along the calculated path. Szczerba et al. (Citation2000) presented the sparse A-star search (SAS) for path planning, and this algorithm effectively reduces the computation complexity by adding constraints to space searching during path planning. Stentz (Citation1994) developed the dynamic A-star algorithm, which is also known as D-star algorithm for partially or completely unknown dynamic environment. It is capable of updating the map from unknown environments and replanning the path when detecting new obstacles on its path. The sampling-based path planning algorithm, such as the rapidly exploring random trees (RRT) proposed by Yershova et al. (Citation2005), can keep motion path planning from failure when there is no prior information of the environment provided.

4.1.2. Intelligent algorithms

In recent years, researchers tried to use intelligent algorithms to solve global path planning problems, and propose lots of intelligent searching methods. Among those, the most popular intelligent algorithms are genetic algorithm and simulate anneal arithmetic (SAA) algorithm. In (Zhang, Ma, and Liu Citation2012), the genetic algorithm and SAA methods are applied into the study of path planning. The adaptation function of the path is evaluated using crossover and mutation operation in genetic algorithm and Metropolis criterion, which improve the efficiency of path planning. In (Andert and Adolf Citation2009), the improved simulated annealing algorithm and the conjugate direction method are used to optimize the global path planning.

4.2. Local path planning

Local path planning is based on the local environment information and UAVs’ own state estimation, and aims to dynamically plan a local path without collision. Due to the uncertain factors, such as the movements of objects in the dynamic environment, the path planning in the dynamic environment becomes a high complexity problem. In this case, the path planning algorithms are required to be adaptive to the dynamic characteristics of the environment, by obtaining information (such as the size, shape, and location) about unknown parts of the environment through a variety of sensors.

Traditional local path planning methods consist of spatial search methods, artificial potential field methods, fuzzy logic methods, neural network methods, and so on. Several typical local path planning methods are reviewed below.

Artificial potential field method is a kind of virtual force method proposed by Sugihara and Suzuki (Citation1996), whose basic idea is to move a robot from the surrounding environment into an abstract artificial gravitational field environment. The target point has the “attraction” as well as the obstacle with “repulsion” to the mobile robot, so the robot is controlled by these two forces and gradually moves toward the target point. Bortoff (Citation2000) gave an example of the use of the artificial potential field method for calculating the path through the radar threat area.

Genetic algorithm provides a general framework for solving complex optimization problems, especially for calculating an optimal path. It follows the inheritance and evolution of biological phenomena. According to the principle of “survival competition and survival of the fittest,” the problems can be solved to obtain an optimal solution. It is composed of five main components, including chromosome coding, initial population, fitness function, genetic operation, and control parameters. Many literatures use the genetic algorithm as aircraft path planning solution (Pellazar Citation1998).

Neural network is a computational method established under the revelation of biological functions. Gilmore and Czuchry (Citation1992) gave an example of a path planning using Hopfield networks. The ant colony algorithm is a new kind of bionic algorithm that mimics the ant activity (Parunak, Purcell, and O’Connell Citation2002). As a stochastic optimization method, it imitates the behavioral characteristics of ants, so it could achieve results through a solution of a series of difficult combinatorial optimizations.

5. Conclusions

With the rapid development of computer vision and the growing popularity of small UAVs, the combination of them has been an active area of research (Szeliski Citation2010). This paper mainly introduces the vision-based navigation of UAVs from three aspects: localization and mapping, obstacle avoidance and path planning. Localization and mapping is the key of autonomous navigation, which also provides location and environmental information for UAVs. Obstacle avoidance and path planning are essential for the UAV to safely and quickly get to the target location without collision.

Even though UAVs are sharing similar navigation solution with ground mobile robots, we are still facing many challenges when it refers to vision-based UAV navigation. The UAV needs to process amount of sensors’ information in real time in order to fly safely and steady, especially for image processing which greatly increase the computational complexity. So it has become a major challenge a UAV to navigate under constraints of low power consumption and limited computing resources.

Besides, UAV navigation requires a global or local 3D map of the environment; extra dimension means greater computation and storage consumption. So there is a great challenge when a UAV is navigating in a large-scale environment for a long time. In addition to that, motion blur caused by fast movement and rotation can easily result in tracking and localization failure during the flight. Thereby, future research on loop detection and relocalization are expected.

Given a partial or complete 3D map, we are required not only to find a collision-free path, but also to minimize the travel length or energy consumption. Unlike 2D path planning, the difficulties in a 3D map increase exponentially with the growing complexity of dynamic constraints and kinematic constraints of UAVs. So there are no common solutions to this NP-hard problem, and modern path planning algorithms still suffer from the local minimum problem. Therefore, a more robust and global optimization algorithm is still under research.

To date, the problem of vision-based UAV navigation, which uses visual sensors as the only external sensors for dynamic, complex and large-scale environments, remains to be solved and is a prosperous area of research (Jones Citation2009; Márquez-Gámez Citation2012; Mirowski et al. Citation2017).

Considering the trends that sensors are getting smaller as well as more precise, UAVs can be equipped with multiple types of sensors. However, problems often occur when it comes to fusing different types of sensor data, which have different noise characteristics and poor synchronization. Despite this, benefiting from multi-sensor data fusion, we are expected to obtain better pose estimation, which can greatly improve the performance of navigation (Shen et al. Citation2014). Currently, as the inertial measurement unit is getting smaller and cheaper, fusing IMU and visual measurement together is gaining much more attention (Leutenegger et al. Citation2015).

We have also found that the limited power and perception ability make it infeasible for a single UAV to complete certain types of tasks. So far, with the improvement of autonomous navigation, it is becoming possible for multiple UAVs to complete such tasks together (Maza et al. Citation2011; Han and Chen Citation2014).

Although we have made some impressive progress in vision-based navigation, there are still many problems to be solved before a fully autonomous navigation system coming true, such as autonomously avoiding obstacles, generating an optimal path in dynamic scenarios, and updating and assigning tasks dynamically (Roberge, Tarbouchi, and Labonté Citation2013).

Finally, we make a list of the most important algorithms referenced in this survey. Table enumerates the algorithms of localization and mapping highlighted in this survey. Table enumerates the methods in obstacle detection and avoidance. Table enumerates the methods in path planning.

Table 1. Summary of important methods in localization and mapping.

Table 2. Summary of important methods in obstacle detection and avoidance.

Table 3. Summary of important methods in path planning.

Notes on contributors

Yuncheng Lu is a postgraduate at State Key Laboratory of Information Engineering in Surveying, Mapping and Remote Sensing (LIESMARS), Wuhan University, China. He received the BS degree in Electronic Information School from Wuhan University in 2016. He majors in photogrammetry and remote sensing and his research interests include monocular and RGB-D SLAM and their applications in UAVs.

Zhucun Xue is a postgraduate at State Key Laboratory of Information Engineering in Surveying, Mapping and Remote Sensing (LIESMARS), Wuhan University, China. She received the BS degree in Electronic Information School from Wuhan University in 2017. Her research interests include monocular visual SLAM and deep learning.

Gui-song Xia is a professor at State Key Laboratory of Information Engineering in Surveying, Mapping and Remote Sensing (LIESMARS), Wuhan University, China. He received the BS degree in electronics engineering and the MS degree in signal processing from Wuhan University, Wuhan, China, in 2005 and 2007, respectively, and the PhD degree in image processing and computer vision from the Centre National de la Recherche Scientifique (CNRS) Laboratoire Traitement et Communication de l’Information (LTCI), TELECOM ParisTech, Paris, France, in 2011. Since April 2011, he had worked as a postdoctoral researcher at CNRS (LTCI and CEREMADE) for about 1.5 years. His current research concentrates on mathematical modeling of images, computer vision, pattern recognition, and their applications in remote sensing imaging. On those topics, he has co-/authored more than 90 articles on international journals/conferences. He serves currently as an associate editor of EURASIP Journal on Image and Video Processing and Area Editors of the journal Signal Processing: Image Communications, and Guest Editor of IEEE Trans. on Big Data, Pattern Recognition Letter, Geo-Spatial Information Science, etc. He is a senior member of IEEE and also serves as the associate chair of Wuhan Chapter of IEEE Signal Processing Society (SPS).

Liangpei Zhang received the BS degree in physics from Hunan Normal University, Changsha, China, in 1982, the MS degree in optics from the Xi’an Institute of Optics and Precision Mechanics, Chinese Academy of Sciences, Xi’an, China, in 1988, and the Ph.D. degree in photogrammetry and remote sensing from Wuhan University, Wuhan, China, in 1998. He is currently a Chang-Jiang Scholar Chair Professor at Wuhan University appointed by the Ministry of Education of China. He has published more than 500 research papers and five books. He also holds 15 patents. His research interests include hyperspectral remote sensing, high-resolution remote sensing, image processing, and artificial intelligence. He is a fellow of the Institution of Engineering and Technology, an executive member (Board of Governors) of the China National Committee of International Geosphere-Biosphere Programme, and an executive member of the China Society of Image and Graphics. He regularly serves as a co-chair of the series SPIE Conferences on Multispectral Image Processing and Pattern Recognition, Conference on Asia Remote Sensing, and many other conferences. He edits several conference proceedings, issues, and geoinformatics symposiums. He also serves as an associate editor of International Journal of Ambient Computing and Intelligence, International Journal of Image and Graphics, International Journal of Digital Multimedia Broadcasting, and Journal of Remote Sensing. He is currently serving as an associate editor of IEEE Transactions on Geoscience and Remote Sensing.

Funding

This work was supported by the National Natural Science Foundation of China [grant number 61771350]. It was also partially supported by the Open Research Fund of Key Laboratory of Space Utilization, Chinese Academy of Sciences [grant number LSU-SJLY-2017-01]; and the Open Research Fund of State Key Laboratory of Tianjin Key Laboratory of Intelligent Information Processing in Remote Sensing [grant number 2016-ZW-KFJJ02].

References

  • Al-Kaff, A., Q. Meng, D. Martín, A. de la Escalera, and J. M. Armingol. 2016. “Monocular Vision-based Obstacle Detection/Avoidance for Unmanned Aerial Vehicles.” Intelligent Vehicles Symposium, IEEE, Gothenburg, Sweden, June 19–22.
  • Andert, F., and F. Adolf. 2009. “Online World Modeling and Path Planning for an Unmanned Helicopter.” Autonomous Robots 27 (3): 147–164.10.1007/s10514-009-9134-y
  • Araar, O., and N. Aouf. 2014. “A New Hybrid Approach for the Visual Servoing of VTOL UAVs from Unknown Geometries.” Paper Presented at the Control and Automation, 22nd Mediterranean Conference of, Palermo, Italy, June 16–19.
  • Aulinas, J., Y. R. Petillot, J. Salvi, and X. Lladó. 2008. “The SLAM Problem: A Survey.” Conference on Artificial Intelligence Research and Development, 11th International Conference of the Catalan Association for Artificial Intelligence, Spain, October 22–24.
  • Bai, G., X. Xiang, H. Zhu, D. Yin, and L. Zhu. 2015. “Research on Obstacles Avoidance Technology for UAV Based on Improved PTAM Algorithm.” Paper Presented at the Progress in Informatics and Computing, IEEE International Conference on, Nanjing, China, December 18–20.
  • Bertrand, O. J., J. P. Lindemann, and M. Egelhaaf. 2015. “A Bio-Inspired Collision Avoidance Model Based on Spatial Information Derived from Motion Detectors Leads to Common Routes.” PLoS Computational Biology 11 (11): e1004339.10.1371/journal.pcbi.1004339
  • Bonin-Font, F., A. Ortiz, and G. Oliver. 2008. “Visual Navigation for Mobile Robots: A Survey.” Journal of Intelligent and Robotic Systems 53 (3): 263–296.10.1007/s10846-008-9235-4
  • Bortoff, S. A. 2000. “Path Planning for UAVs.” Paper Presented at the American Control Conference, IEEE, Chicago, IL, USA, June 8–30.
  • Carrillo, L. R. G., A. E. D. López, R. Lozano, and C. Pégard. 2012. “Combining Stereo Vision and Inertial Navigation System for a Quad-Rotor UAV.” Journal of Intelligent & Robotic Systems 65 (1–4): 373–387.10.1007/s10846-011-9571-7
  • Celik, K., S. J. Chung, M. Clausman, and A. K. Somani. 2009. “Monocular Vision SLAM for Indoor Aerial Vehicles.” Paper Presented at the Intelligent Robots and Systems, IEEE/RSJ International Conference on, St. Louis, USA, October10–15.
  • Cho, D., P. Tsiotras, G. Zhang, and M. Holzinger. 2013. “Robust Feature Detection, Acquisition and Tracking for Relative Navigation in Space with a Known Target.” Paper Presented at the AIAA Guidance, Navigation, and Control Conference, Boston, MA, August 19–22.
  • Davison, A. J. 2003. “Real-Time Simultaneous Localisation and Mapping with a Single Camera.” Paper Presented at the Computer Vision, IEEE International Conference on, Nice, France, October 13–16.
  • Desouza, G. N., and A. C. Kak. 2002. “Vision for Mobile Robot Navigation: A Survey.” IEEE Transactions on Pattern Analysis and Machine Intelligence 24 (2): 237–267.10.1109/34.982903
  • Dryanovski, I., W. Morris, and J. Xiao. 2010. “Multi-Volume Occupancy Grids: An Efficient Probabilistic 3D Mapping Model for Micro Aerial Vehicles.” Paper Presented at the Intelligent Robots and Systems, IEEE/RSJ International Conference on, Taipei, China, October 18–22.
  • Engel, J., T. Schöps, and D. Cremers. 2014. “LSD-SLAM: Large-scale Direct Monocular SLAM.” Paper presented at the European Conference on Computer Vision, Zurich, Switzerland, September 6–12, 834–849.
  • Esrafilian, O., and H. D. Taghirad. 2016. “Autonomous Flight and Obstacle Avoidance of a Quadrotor by Monocular SLAM.” Paper Presented at the Robotics and Mechatronics, 4th IEEE International Conference on, Tehran, Iran, October 26–28.
  • Forster, C., M. Pizzoli, and D. Scaramuzza. 2014. “SVO: Fast Semi-direct Monocular Visual Odometry.” Paper Presented at the Robotics and Automation, IEEE International Conference on, Hong Kong, China, May 31–June 7.
  • Forster, C., M. Faessler, F. Fontana, M. Werlberger, and D. Scaramuzza. 2015. “Continuous On-board Monocular-vision-based Elevation Mapping Applied to Autonomous Landing of Micro Aerial Vehicles.” Paper Presented at the Robotics and Automation, IEEE International Conference on, Seattle, USA, May 26–30.
  • Fournier, J., B. Ricard, and D. Laurendeau. 2007. “Mapping and Exploration of Complex Environments Using Persistent 3D Model.” Paper Presented at the Computer and Robot Vision, Fourth Canadian Conference on, IEEE, Montreal, Canada, May 28–30.
  • Gageik, N., P. Benz, and S. Montenegro. 2015. “Obstacle Detection and Collision Avoidance for a UAV with Complementary Low-Cost Sensors.” IEEE Access 3: 599–609.10.1109/ACCESS.2015.2432455
  • Gaspar, J., N. Winters, and J. Santos-Victor. 2000. “Vision-Based Navigation and Environmental Representations with an Omnidirectional Camera.” IEEE Transactions on Robotics and Automation 16 (6): 890–898.10.1109/70.897802
  • Gilmore, J. F., and A. J. Czuchry. 1992. “A Neural Network Model for Route Planning Constraint Integration.” Paper Presented at the Neural Networks, IEEE International Joint Conference on, Baltimore, MD, USA, June 7–11.
  • Gosiewski, Z., J. Ciesluk, and L. Ambroziak. 2011. “Vision-Based Obstacle Avoidance for Unmanned Aerial Vehicles.” Paper Presented at the Image and Signal Processing, 4th IEEE International Congress on, Shanghai, China, October 15–17.
  • Gutmann, J., M. Fukuchi, and M. Fujita. 2008. “3D Perception and Environment Map Generation for Humanoid Robot Navigation.” The International Journal of Robotics Research 27 (10): 1117–1134.10.1177/0278364908096316
  • Haag, J., W. Denk, and A. Borst. 2004. “Fly Motion Vision is Based on Reichardt Detectors regardless of the Signal-to-Noise Ratio.” Proceedings of the National Academy of Sciences of the United States of America 101 (46): 16333–16338.10.1073/pnas.0407368101
  • Han, J., and Y. Chen. 2014. “Multiple UAV Formations for Cooperative Source Seeking and Contour Mapping of a Radiative Signal Field.” Journal of Intelligent & Robotic Systems 74 (1–2): 323–332.10.1007/s10846-013-9897-4
  • Harmat, A., M. Trentini, and I. Sharf. 2015. “Multi-camera Tracking and Mapping for Unmanned Aerial Vehicles in Unstructured Environments.” Journal of Intelligent & Robotic Systems 78 (2): 291–317.10.1007/s10846-014-0085-y
  • Herissé, B., T. Hamel, R. Mahony, and F. Russotto. 2012. “Landing a VTOL Unmanned Aerial Vehicle on a Moving Platform Using Optical Flow.” IEEE Transactions on Robotics 28 (1): 77–89.10.1109/TRO.2011.2163435
  • Herwitz, S. R., L. F. Johnson, S. E. Dunagan, R. G. Higgins, D. V. Sullivan, J. Zheng, and B. M. Lobitz. 2004. “Imaging from an Unmanned Aerial Vehicle: Agricultural Surveillance and Decision Support.” Computers and Electronics in Agriculture 44 (1): 49–61.10.1016/j.compag.2004.02.006
  • Horn, B. K., and B. G. Schunck. 1981. “Determining Optical Flow.” Artificial Intelligence 17 (1–3): 185–203.10.1016/0004-3702(81)90024-2
  • Hornung, A., K. M. Wurm, M. Bennewitz, C. Stachniss, and W. Burgard. 2013. “OctoMap: An Efficient Probabilistic 3D Mapping Framework Based on Octrees.” Autonomous Robots 34 (3): 189–206.10.1007/s10514-012-9321-0
  • How, J. P., B. Behihke, A. Frank, D. Dale, and J. Vian. 2008. “Real-time Indoor Autonomous Vehicle Test Environment.” IEEE Control Systems 28 (2): 51–64.10.1109/MCS.2007.914691
  • Hrabar, S. 2008. “3D Path Planning and Stereo-based Obstacle Avoidance for Rotorcraft UAVs.” Paper Presented at the Intelligent Robots and Systems, IEEE/RSJ International Conference on, Nice, France, September 22–26.
  • Jones, E. S. 2009. “Large Scale Visual Navigation and Community Map Building.” PhD diss., University of California at Los Angeles.
  • Klein, G., and D. Murray. 2007. “Parallel Tracking and Mapping for Small AR Workspaces.” Paper Presented at the Mixed and Augmented Reality, 6th IEEE and ACM International Symposium on, Nara, Japan, November 13–16.
  • Kümmerle, R., G. Grisetti, H. Strasdat, K. Konolige, and W. Burgard. 2011. “g2o: A General Framework for Graph Optimization.” Paper Presented at the Robotics and Automation, IEEE International Conference on, Shanghai, China, May 9–13.
  • Langelaan, J. W., and N. Roy. 2009. “Enabling New Missions for Robotic Aircraft.” Science 326 (5960): 1642–1644.10.1126/science.1182497
  • Leutenegger, S., S. Lynen, M. Bosse, R. Siegwart, and P. Furgale. 2015. “Keyframe-Based Visual–inertial Odometry Using Nonlinear Optimization.” The International Journal of Robotics Research 34 (3): 314–334.10.1177/0278364914554813
  • Li, J., and N. M. Allinson. 2008. “A Comprehensive Review of Current Local Features for Computer Vision.” Neurocomputing 71 (10): 1771–1787.10.1016/j.neucom.2007.11.032
  • Li, H., and S. X. Yang. 2003. “A Behavior-based Mobile Robot with a Visual Landmark-recognition System.” IEEE/ASME Transactions on Mechatronics 8 (3): 390–400.10.1109/TMECH.2003.816818
  • Lucas, B. D., and T. Kanade. 1981. “An Iterative Image Registration Technique with an Application to Stereo Vision.” Paper Presented at the DARPA Image Understanding Workshop, 7th International Joint Conference on Artificial Intelligence, Vancouver, Canada, August 24–28.
  • Lynen, S., M. W. Achtelik, S. Weiss, M. Chli, and R. Siegwart. 2013. “A Robust and Modular Multi-Sensor Fusion Approach Applied to Mav Navigation.” Paper Presented at the Intelligent Robots and Systems, IEEE/RSJ International Conference on, Tokyo, Japan, November 3–7.
  • Magree, D., and E. N. Johnson. 2014. “Combined Laser and Vision-Aided Inertial Navigation for an Indoor Unmanned Aerial Vehicle.” Paper Presented at the American Control Conference, IEEE, Portland, USA, June 4–6.
  • Mahon, I., S. B. Williams, O. Pizarro, and M. Johnson-Roberson. 2008. “Efficient View-based SLAM Using Visual Loop Closures.” IEEE Transactions on Robotics 24 (5): 1002–1014.10.1109/TRO.2008.2004888
  • Maier, J., and M. Humenberger. 2013. “Movement Detection Based on Dense Optical Flow for Unmanned Aerial Vehicles.” International Journal of Advanced Robotic Systems 10 (2): 146. 10.5772/52764
  • Márquez-Gámez, D. 2012. “Towards Visual Navigation in Dynamic and Unknown Environment: Trajectory Learning and following, with Detection and Tracking of Moving Objects.” PhD diss., l’Institut National des Sciences Appliquées de Toulouse.
  • Matsumoto, Y., K. Ikeda, M. Inaba, and H. Inoue. 1999. “Visual Navigation Using Omnidirectional View Sequence.” Paper Presented at the Intelligent Robots and Systems, IEEE/RSJ International Conference on, Kyongju, South Korea, October17–21.
  • Maza, I., F. Caballero, J. Capitán, J. R. Martínez-de-Dios, and A. Ollero. 2011. “Experimental Results in Multi-UAV Coordination for Disaster Management and Civil Security Applications.” Journal of Intelligent & Robotic Systems 61 (1): 563–585.10.1007/s10846-010-9497-5
  • Mirowski, P., R. Pascanu, F. Viola, H. Soyer, A. Ballard, A. Banino, and M. Denil. 2017. “Learning to Navigate in Complex Environments.” The 5th International Conference on Learning Representations, Toulon, France, April 24–26.
  • Moravec, H. P. 1983. “The Stanford Cart and the CMU Rover.” Proceedings of the IEEE 71 (7): 872–884.10.1109/PROC.1983.12684
  • Moreno-Armendáriz, M. A., and H. Calvo. 2014. “Visual SLAM and Obstacle Avoidance in Real Time for Mobile Robots Navigation.” Paper Presented at the Mechatronics, Electronics and Automotive Engineering (ICMEAE), IEEE International Conference on, Cuernavaca, Mexico, November 18–21.
  • Newcombe, R. A., S. J. Lovegrove, and A. J. Davison. 2011. “DTAM: Dense Tracking and Mapping in Real-time.” Paper Presented at the Computer Vision (ICCV), IEEE International Conference on, Washington, DC, USA, November 6–13.
  • Nourani-Vatani, N., P. Vinicius, K. Borges, J. M. Roberts, and M. V. Srinivasan. 2014. “On the Use of Optical Flow for Scene Change Detection and Description.” Journal of Intelligent & Robotic Systems 74 (3–4): 817.10.1007/s10846-013-9840-8
  • Parunak, H. V., M. Purcell, and R. O’Connell. 2002. “Digital Pheromones for Autonomous Coordination of Swarming UAV’s.” Paper Presented at the 1st UAV Conference, Portsmouth, Virginia, May 20–23.
  • Pellazar, M. B. 1998. “Vehicle Route Planning with Constraints Using Genetic Algorithms”. Paper Presented at the Aerospace and Electronics Conference, NAECON, 1998, IEEE National, Dayton, USA, July 17.
  • Ranftl, R., V. Vineet, Q. Chen, and V. Koltun. 2016. “Dense Monocular Depth Estimation in Complex Dynamic Scenes.” Paper Presented at the Computer Vision and Pattern Recognition, IEEE Conference on, Las Vegas, USA, June 27–30.
  • Roberge, V., M. Tarbouchi, and G. Labonté. 2013. “Comparison of Parallel Genetic Algorithm and Particle Swarm Optimization for Real-time UAV Path Planning.” IEEE Transactions on Industrial Informatics 9 (1): 132–141.10.1109/TII.2012.2198665
  • Rogers, B., and M. Graham. 1979. “Motion Parallax as an Independent Cue for Depth Perception.” Perception 8 (2): 125–134.10.1068/p080125
  • Rouse, D. M. 1989. “Route Planning Using Pattern Classification and Search Techniques.” Aerospace and Electronics Conference, IEEE National, Dayton, USA, May 22–26.
  • Ruffier, F., S. Viollet, S. Amic, and N. Franceschini. 2003. “Bio-inspired Optical Flow Circuits for the Visual Guidance of Micro Air Vehicles.” Paper Presented at the Circuits and Systems, IEEE International Symposium on, Bangkok, Thailand, May 25–28.
  • Santos-Victor, J., G. Sandini, F. Curotto, and S. Garibaldi. 1993. “Divergent Stereo for Robot Navigation: Learning from Bees.” Paper Presented at the Computer Vision and Pattern Recognition, IEEE Computer Society Conference on, New York, USA, June 15–17.
  • Seitz, S. M., B. Curless, J. Diebel, D. Scharstein, and R. Szeliski. 2006. “A Comparison and Evaluation of Multi-view Stereo Reconstruction Algorithms.” Paper Presented at the Computer Vision and Pattern Recognition, IEEE Computer Society Conference on, New York, USA, June 17–22.
  • Shen, S., Y. Mulgaonkar, N. Michael, and V. Kumar. 2014. “Multi-Sensor Fusion for Robust Autonomous Flight in Indoor and Outdoor Environments with a Rotorcraft MAV.” Paper Presented at the Robotics and Automation (ICRA), IEEE International Conference on, Hong Kong, China, May 31–June 7.
  • Silveira, G., E. Malis, and P. Rives. 2008. “An Efficient Direct Approach to Visual SLAM.” IEEE Transactions on Robotics 24 (5): 969–979.10.1109/TRO.2008.2004829
  • Srinivasan, M. V., and R. L. Gregory. 1992. “How Bees Exploit Optic Flow: Behavioural Experiments and Neural Models [and Discussion].” Philosophical Transactions of the Royal Society of London B: Biological Sciences 337 (1281): 253–259.10.1098/rstb.1992.0103
  • Stentz, A. 1994. “Optimal and Efficient Path Planning for Partially-Known Environments.” Paper Presented at the IEEE International Conference on Robotics and Automation, San Diego, CA, USA, May 8–13.
  • Strasdat, H., J. M. Montiel, and A. J. Davison. 2012. “Visual SLAM: Why Filter?” Image and Vision Computing 30 (2): 65–77.10.1016/j.imavis.2012.02.009
  • Strohmeier, M., M. Schäfer, V. Lenders, and I. Martinovic. 2014. “Realities and Challenges of Nextgen Air Traffic Management: The Case of ADS-B.” IEEE Communications Magazine 52 (5): 111–118.10.1109/MCOM.2014.6815901
  • Sugihara, K., and I. Suzuki. 1996. “Distributed Algorithms for Formation of Geometric Patterns with Many Mobile Robots.” Journal of Robotic Systems 13 (3): 127–139.10.1002/(SICI)1097-4563(199603)13:3<>1.0.CO;2-Z
  • Szczerba, R. J., P. Galkowski, I. S. Glicktein, and N. Ternullo. 2000. “Robust Algorithm for Real-time Route Planning.” IEEE Transactions on Aerospace and Electronic Systems 36 (3): 869–878.10.1109/7.869506
  • Szeliski, R. 2010. Computer Vision: Algorithms and Applications. London: Springer Science & Business Media.
  • Szenher, M. D. 2008. “Visual Homing in Dynamic Indoor Environments.” PhD diss., University of Edinburgh.
  • Tuytelaars, T., and K. Mikolajczyk. 2008. “Local Invariant Feature Detectors: A Survey.” Foundations and Trends in Computer Graphics and Vision 3 (3): 177–280.
  • Vachtsevanos, G., W. Kim, S. Al-Hasan, F. Rufus, M. Simon, D. Shrage, and J. Prasad. 1997. “Autonomous Vehicles: From Flight Control to Mission Planning Using Fuzzy Logic Techniques.” Paper Presented at the Digital Signal Processing, 13th International Conference on, IEEE, Santorini, Greece, July 2–4.
  • Valgaerts, L., A. Bruhn, M. Mainberger, and J. Weickert. 2012. “Dense versus Sparse Approaches for Estimating the Fundamental Matrix.” International Journal of Computer Vision 96 (2): 212–234.10.1007/s11263-011-0466-7
  • Yershova, A., L. Jaillet, T. Simeon, and S. M. Lavalle. 2005. “Dynamic-Domain RRTs: Efficient Exploration by Controlling the Sampling Domain.” Paper Presented at the IEEE International Conference on Robotics and Automation, Barcelona, Spain, April 18–22.
  • Zhang, Q., J. Ma, and Q. Liu. 2012. “Path Planning Based Quadtree Representation for Mobile Robot Using Hybrid-Simulated Annealing and Ant Colony Optimization Algorithm.” Paper Presented at The Intelligent Control and Automation (WCICA), 10th World Congress on, IEEE, Beijing, China, July 6–8.