Code for Autonomous Drone Race is now available on GitHub

We release Teach-Repeat-Replan, which is a complete and robust system enables Autonomous Drone Race.

Teach-Repeat-Replan can be applied to situations where the user has a preferable rough route but isn’t able to pilot the drone ideally, such as drone racing. With our system, the human pilot can virtually control the drone with his/her navie operations, then our system automatically generates a very efficient repeating trajectory and autonomously execute it. During the flight, unexpected collisions are avoided by onboard sensing/replanning. Teach-Repeat-Replan can also be used for normal autonomous navigations. For these applications, a drone can autonomously fly in complex environments using only onboard sensing and planning.

Major components are:

  • Planning: flight corridor generation, global spatial-temporal planning, local online re-planning
  • Perception: global deformable surfel mapping, local online ESDF mapping
  • Localization: global pose graph optimization, local visual-inertial fusion
  • Controlling: geometric controller on SE(3)

Authors: Fei Gao, Boyu Zhou, and Shaojie Shen

Videos: Video1Video2
Code: https://github.com/HKUST-Aerial-Robotics/Teach-Repeat-Replan

Autonomous drone racing

In this video, we showcase aggressive autonomous drone races.

The drone is equipped with a pair of stereo cameras and a DJI N3 flight controller. All computing during the flight is done onboard. Our system consists of visual-inertial SLAM with loop closure, global mapping, local mapping, global trajectory optimization, local re-planning, and human-drone interaction interfaces.

Our system is built upon on a teach-and-repeat framework. A dense and globally consistent map is built before each experiment. In the teaching phase, the drone is piloted to provide a topological path (i.e. where hula hoop the drone should go through). In the repeating/execution phase, the drone converts the teaching path into a topologically equivalent optimal trajectory based on the known global obstacle map. The drone then executes the trajectory with user-expected velocity. The execution velocity can differ from that in the teaching phase. In fact, the drone operates much more aggressively during the execution phase thanks to the optimal trajectory generation. In the execution phase, state estimation and mapping functions maintain, such that the drone can avoid any new obstacles not identified in the global maps. Vision-based loop closure guarantees that the drone can operate in the same coordinate system for both the teaching and the repeating phase.

We target for better performance beyond human in challenging drone racing scenarios. Four video clips are presented to showcase the performance in indoor and outdoor, static and dynamic environments:
1. Indoor autonomous drone racing in a static environment
2. Indoor autonomous drone racing in an environment with unknown obstacles
3. Outdoor autonomous drone racing, trial 1
4. Outdoor autonomous drone racing, trial 2

Tong Qin wins IROS 2018 Best Student Paper Award

On October 4th 2018, the paper "Online temporal calibration for monocular visual-inertial systems" by Ph.D. student Tong Qin wins the Best Student Paper Award in the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2018) at Madrid, Spain.

In this paper, we propose an online approach for calibrating temporal offset between visual and inertial measurements. Our approach achieves temporal offset calibration by jointly optimizing time offset, camera and IMU states, as well as feature locations in a SLAM system. Furthermore, the approach is a general model, which can be easily employed in several feature-based optimization frameworks. Simulation and experimental results demonstrate the high accuracy of our calibration approach even compared with other state-of-art offline tools. The VIO comparison against other methods proves that the online temporal calibration significantly benefits visual-inertial systems. The source code of temporal calibration is integrated into our public project, VINS-Mono.

IROS 2018

Code for VINS-Mono is now available on GitHub

A Robust and Versatile Monocular Visual-Inertial State Estimator

VINS-Mono is a real-time SLAM framework for Monocular Visual-Inertial Systems. It uses an optimization-based sliding window formulation for providing high-accuracy visual-inertial odometry. It features efficient IMU pre-integration with bias correction, automatic estimator initialization, online extrinsic calibration, failure detection and recovery, loop detection, and global pose graph optimization. VINS-Mono is primarily designed for state estimation and feedback control of autonomous drones, but it is also capable of providing accurate localization for AR applications. This code runs on Linux, and is fully integrated with ROS. For iOS mobile implementation, please go to VINS-Mobile.

Authors: Tong Qin, Peiliang Li, Zhenfei Yang, and Shaojie Shen from the HUKST Aerial Robotics Group

Code: https://github.com/HKUST-Aerial-Robotics/VINS-Mono

Videos:

EuRoC dataset

Indoor and outdoor performance

AR application

MAV application

Mobile implementation

Code for VINS-Mobile is now available on GitHub

Monocular Visual-Inertial State Estimator on Mobile Phones

VINS-Mobile is a real-time monocular visual-inertial state estimator developed by members of the HKUST Aerial Robotics Group. It runs on compatible iOS devices, and provides localization services for augmented reality (AR) applications. It is also tested for state estimation and feedback control for autonomous drones. VINS-Mobile uses sliding window optimization-based formulation for providing high-accuracy visual-inertial odometry with automatic initialization and failure recovery. The accumulated odometry errors are corrected in real-time using global pose graph SLAM. An AR demonstration is provided to showcase its capability.

Authors: Peiliang LI, Tong QIN, Zhenfei YANG, Kejie QIU, and Shaojie SHEN

Code: https://github.com/HKUST-Aerial-Robotics/VINS-Mobile

 

Fei GAO received 2016 IEEE-SSRR Best Conference Paper Award

Fei GAO received 2016 IEEE-SSRR Best Conference Paper Award

The paper “Online quadrotor trajectory generation and autonomous navigation on point clouds” by Ph.D. student Fei GAO just won the Best Conference Paper Award in the 2016 IEEE International Symposium on Safety, Security, and Rescue Robotics (SSRR) at Lausanne, Switzerland. Our group got the best paper award for this conference two years in a row.read more

Trajectory Generation for Aerial Robots

We develop online methods to generate safe and smooth trajectories for aerial navigation through unknown, complex, and possibly dynamic environments. We use convex optimization tools to ensure both collision avoidance and dynamic feasibility.

Micro aerial vehicles (MAVs), especially quadrotors, have drawn increasing attention in recent years thanks to their superior mobility in complex environments that are inaccessible or dangerous for human or other ground vehicles. In autonomous navigation missions, quadrotors should be able to online generate and execute smooth and safe trajectories from a start position to a target position, while avoiding unexpected obstacles. The generated trajectories should have the guarantee of safety and smoothness considering the dynamic ability of the quadrotor.

img_4506In this project, some novel methods are developed to generate safe and smooth trajectories in cluttered environments. Based on good localization and mapping techniques, a flight corridor with safety guarantee is obtained in the cluttered environments first, following an optimization-based algorithm to assign a global optimal trajectory within the flight corridor entirely. Our works are implemented onboard a quadrotor and are suitable for fast online re-planning, making them able to work in unknown dynamic environments with unexpected obstacles.

Our algorithms can be widely used on various types of mapping modules, such as laser-based octomap and point clouds or monocular dense mapping. Both simulation results and indoor and outdoor autonomous flights in unknown cluttered environments show the good performance of our methods.

 

Gradient-based online safe trajectory generation for quadrotor flight in complex environments

By Fei GAO

We propose a trajectory generation framework for quadrotor autonomous navigation in unknown 3-D complex environments using gradient information. We decouple the trajectory generation problem as front-end path searching and back-end trajectory refinement. Based on the map that is incrementally built onboard, we adopt a sampling- based informed path searching method to find a safe path passing through obstacles. We convert the path consists of line segments to an initial safe trajectory. An optimization- based method which minimizes the penalty of collision cost, smoothness and dynamical feasibility is used to refine the trajectory. Our method shows the ability to online gener- ate smooth and dynamical feasible trajectories with safety guarantee. We integrate the state estimation, dense mapping and motion planning module into a customized light-weight quadrotor platform. We validate our proposed method by presenting fully autonomous navigation in unknown cluttered indoor and outdoor environments.

 

Tracking a moving target in cluttered environments using a quadrotor

By Jing CHEN

We address the challenging problem of tracking a moving target in cluttered environments using a quadrotor. Our online trajectory planning method generates smooth, dynamically feasible, and collision-free polynomial trajectories that follow a visually-tracked moving target. As visual observations of the target are obtained, the target trajectory can be estimated and used to predict the target motion for a short time horizon. We propose a formulation to embed both limited horizon tracking error and quadrotor control costs in the cost function for a quadratic programming (QP), while encoding both collision avoidance and dynamical feasibility as linear inequality constraints for the QP. Our method generates tracking trajectories in the order of milliseconds and is therefore suitable for online target tracking with a limited sensing range. We implement our approach on-board a quadrotor testbed equipped with cameras, a laser range finder, an IMU, and onboard computing. Statistical analysis, simulation, and real-world experiments are conducted to demonstrate the effectiveness of our approach.

 

Online quadrotor trajectory generation and autonomous navigation on point clouds

By Fei GAO

We present a framework for online generation of safe trajectories directly on point cloud for autonomous quadrotor flight. Considering a quadrotor operating in unknown environments, we use a 3-D laser range finder for state estimation and simultaneously build a point cloud map of the environment. Based on the incrementally built point cloud map, we utilize the property of the fast nearest neighbor search in KD-tree and adopt the sampling-based path finding method to generate a flight corridor with safety guarantee in 3-D space. A trajectory generation method formulated in quadratically constrained quadratic programming (QCQP) is then used to generate trajectories that constrained entirely within the corridor. Our method runs onboard within 100 milliseconds, making it suitable for online re-planning. We integrate the proposed planning method with laser-based state estimation and mapping modules, and demonstrate the autonomous quadrotor flight in unknown indoor and outdoor environments.

 

Online generation of collision-free trajectories for quadrotor flight in unknown cluttered environments

By Jing CHEN

We present an online method for generating collision-free trajectories for autonomous quadrotor flight through cluttered environments. We consider the real-world scenario that the quadrotor aerial robot is equipped with limited sensing and operates in initially unknown environments. During flight, an octree-based environment representation is incrementally built using onboard sensors. Utilizing efficient operations in the octree data structure, we are able to generate free-space flight corridors consisting of large overlapping 3-D grids in an online fashion. A novel optimization-based method then generates smooth trajectories that both are bounded entirely within the safe flight corridor and satisfy higher order dynamical constraints. Our method computes valid trajectories within fractions of a second on a moderately fast computer, thus permitting online re-generation of trajectories for reaction to new obstacles. We build a complete quadrotor testbed with onboard sensing, state estimation, mapping, and control, and integrate the proposed method to show online navigation through complex unknown environments.

 

Improving octree-based occupancy maps using environment sparsity with application to aerial robot navigation

By Jing CHEN

We present an improved octree-based mapping framework for autonomous navigation of mobile robots. Octree is best known for its memory efficiency for representing large-scale environments. However, existing implementations, including the state-of-the-art OctoMap [1], are computationally too expensive for online applications that require frequent map updates and inquiries. Utilizing the sparse nature of the environment, we propose a ray tracing method with early termination for efficient probabilistic map update. We also propose a divide-and-conquer volume occupancy inquiry method which serves as the core operation for generation of free-space configurations for optimization-based trajectory generation. We experimentally demonstrate that our method maintains the same storage advantage of the original OctoMap, but being computationally more efficient for map update and occupancy inquiry. Finally, by integrating the proposed map structure in a complete navigation pipeline, we show autonomous quadrotor flight through complex environments.

 

Quadrotor trajectory generation in dynamic environments using semi-definite relaxation on nonconvex QCQP

By Fei GAO

We present an optimization-based framework for generating quadrotor trajectories which are free of collision in dynamic environments with both static and moving obstacles. Using the finite-horizon motion prediction of moving obstacles, our method is able to generate safe and smooth trajectories with minimum control efforts. Our method optimizes trajectories globally for all observed moving and static obstacles, such that the avoidance behavior is most unnoticeable. This method first utilizes semi-definite relaxation on a quadratically constrained quadratic programming (QCQP) problem to eliminate the nonconvex constraints in the moving obstacle avoidance problem. A feasible and reasonably good solution to the original nonconvex problem is obtained using a randomization method and convex linear restriction. We detail the trajectory generation formulation and the solving procedure of the nonconvex quadratic program. Our approach is validated by both simulation and experimental results.

 

Invited Talk: RACV 2016

On September 20th 2016, professor Shaojie Shen was invited by the 2016 Symposium on Research and Application in Computer Vision (RACV 2016) to have a talk about “Robust Autonomous Flight in Cluttered Environment”, on the panel of Computer Vision for Robotics at Shanghai Technology University. read more