Review of Multi-rotor Drone Simulation Platforms

With the rapid advancement of technology, the integration of artificial intelligence and robotics is transforming numerous fields, particularly in handling complex tasks. Intelligent robots, leveraging their flexibility and efficiency, are opening new chapters in various applications. Multi-rotor drones, as a crucial carrier of AI in robotics, offer advantages such as low cost, high maneuverability, ease of maintenance, and good stability, making them widely applicable across industries. In cargo transportation, research has delved into path planning and control issues for multi-rotor drones carrying suspended loads, enabling them to adapt to the motion states of goods during transport. Other studies have proposed systems for cooperative transportation using multiple multi-rotor drones, enhancing the flexibility and efficiency of logistics. In agricultural applications, by monitoring crop growth, estimating yields, and identifying diseases, multi-rotor drones significantly improve the management efficiency and precision of agricultural production. Utilizing multi-rotor drones for irrigation also demonstrates advantages in saving human resources and increasing efficiency. In search and rescue scenarios, multi-rotor drones, with their excellent maneuverability and portability, can be quickly deployed to emergency sites. Collaborative multi-drone search and target detection notably accelerate rescue speeds and improve success rates.

From precise agricultural monitoring to complex search and rescue missions, and efficient cargo transportation tasks, multi-rotor drones play an irreplaceable role across various sectors. In the development and application of multi-rotor drones, the accuracy and stability exhibited during task execution are crucial. However, the process to achieve satisfactory results is challenging, especially in developing, debugging, and validating complex flight control algorithms. Conducting these operations directly in real-world environments not only significantly increases costs but also entails substantial risks. Therefore, multi-rotor drone simulation platforms have become essential tools in the development process, saving time and costs, reducing risks in practical execution, and providing a repeatable, reproducible environment for experimenting and validating various flight control algorithms.

Simulation platforms offer a safe, controlled environment, reducing the uncertainties and risks faced by researchers and developers in the physical world, enabling convenient testing and optimization of drone flight control algorithms. By simulating real-world flight conditions, such as specific scenes, lighting variations, obstacle avoidance, etc., developers can efficiently debug and validate algorithms in simulation platforms, ensuring their accuracy and reliability. Furthermore, simulation platforms can mimic various extreme conditions, allowing the robustness of algorithms to be thoroughly tested, which is often difficult or costly to achieve in the real world.

This article explores the evaluation methods for multi-rotor drone simulation platforms: comprehensively considering the perspectives and methods for evaluating simulation platforms from both performance and functional aspects. It summarizes existing traditional solutions and learning-based solutions for multi-rotor drone flight tasks, and further classifies multi-rotor drone simulation platforms based on this. Finally, it lists and explains the characteristics of existing multi-rotor drone simulation platforms and provides an outlook on their future development directions.

Basic Concepts of Multi-rotor Drone Simulation Platforms

Dynamics Model of Multi-rotor Drones

Multi-rotor drones are aircraft systems powered by three or more motors driving propellers, featuring vertical take-off and landing, high maneuverability, and aerial hovering. The following table classifies multi-rotor drones based on the number of rotors.

Table 1: Classification of Multi-rotor Drones
Number of Rotors Layout Schematic Structure and Characteristics
3 Y3 Composed of 3 motors and propellers, distributed in a triangular shape. Simple structure, high maneuverability, relatively small size.
4 QUAD X, QUAD + Composed of 4 motors, symmetrically distributed around the fuselage, with adjacent motors rotating in opposite directions. Simple control, high maneuverability, low cost.
6 HEXA X, HEXA + Composed of 6 motors, symmetrically distributed around the fuselage, with adjacent motors rotating in opposite directions. Balanced structure, good wind resistance and load capacity.
8 OCTO X, OCTO + Composed of 8 motors, symmetrically distributed around the fuselage, with adjacent motors rotating in opposite directions. Balanced structure, good stability, excellent wind resistance and load capacity, higher cost.

This article selects the widely used QUAD X layout quadrotor drone for dynamics model analysis. Typically, a basic quadrotor drone dynamics model is treated as a six-degree-of-freedom point mass with mass \( m \). Performing dynamics analysis on this point mass and establishing the Newton-Euler equations yields the following dynamics formulas:

$$ \begin{align*}
\dot{\mathbf{p}} &= \mathbf{v} \\
m \dot{\mathbf{v}} &= m \mathbf{g} + \mathbf{q} \circ \mathbf{f} \circ \mathbf{q}^{-1} \\
\dot{\mathbf{q}} &= \frac{1}{2} \mathbf{q} \circ \begin{bmatrix} 0 \\ \boldsymbol{\omega} \end{bmatrix} \\
\mathbf{J} \dot{\boldsymbol{\omega}} &= \boldsymbol{\tau} – \boldsymbol{\omega} \times \mathbf{J} \boldsymbol{\omega}
\end{align*} $$

where \( \mathbf{p} \) and \( \mathbf{v} \) represent the position and velocity of the drone’s point mass in the world frame, \( \mathbf{q} \in \text{SO}(3) \) is a quaternion representing the rotation of the body frame relative to the world frame, \( \mathbf{J} \) denotes the drone’s moment of inertia diagonal matrix, \( \mathbf{g} \) is the gravitational acceleration vector, and \( m \) is the drone’s mass.

In the equations, \( \mathbf{f} \) represents the total thrust obtained by the quadrotor drone, and \( \boldsymbol{\tau} \) represents the three-axis moments exerted by the motors on the quadrotor drone. For a quadrotor drone, the calculation formulas are:

$$ \mathbf{f} = \sum_{i=1}^{4} T_i $$

$$ \boldsymbol{\tau} = \sum_{i=1}^{4} \left( \boldsymbol{\tau}_{P,i} + \mathbf{r}_i \times T_i \right) $$

where \( T_i \) represents the thrust from a single motor of the quadrotor drone, and \( \mathbf{r}_i \) represents the position of each motor \( i \) in the body frame.

Equations (1), (2), and (3) constitute the basic dynamics model of a quadrotor drone. Depending on the control level, some simulation platforms further model the motors simply by introducing the motor speed \( \Omega \) variable, modeling the motors as first-order systems, and modeling the relationship between motor thrust, torque, and speed. The most common assumption is that thrust and torque are proportional to the square of the motor speed:

$$ \dot{\Omega} = \frac{1}{k_{\text{mot}}} (\Omega_{\text{cmd}} – \Omega) $$

$$ \begin{align*}
T_i &= c_T \cdot \Omega_i^2 \\
\boldsymbol{\tau}_i &= \begin{bmatrix} 0 & 0 & c_{\tau} \cdot \Omega_i^2 \end{bmatrix}^T
\end{align*} $$

The above model performs well under low-speed conditions or near-hover flight states but neglects the drag experienced by the quadrotor drone during motion. In high-speed flight states, the drag cannot be ignored. To make the model more refined, some simulation platforms incorporate the drag experienced by the drone into the model, improving part of equation (1) by adding the drag effect:

$$ m \dot{\mathbf{v}} = m \mathbf{g} + \mathbf{R} \mathbf{f} – \mathbf{D} \mathbf{v} $$

where \( \mathbf{R} \) is the rotation matrix from the body frame to the world frame, and \( \mathbf{D} \) is a diagonal matrix with elements \( d_x, d_y, d_z \) as the rotor drag coefficients along the three axes, proportional to the square of the drone’s flight speed.

In addition, during drone flight, there are also effects such as rotor drag, interactions between rotors, and interactions between rotors and the body. Considering these effects, to obtain a high-precision model, some modeling approaches use precise simulation calculations of the drone’s fluid dynamics in motion states. However, this approach incurs significant computational cost. Some research uses data-driven methods for fine modeling, which, while approximating the real drone model as closely as possible, effectively saves computational cost. Furthermore, some studies combine basic models with data-driven methods to obtain more accurate models, where data-driven methods are typically used to compensate for the fine details not considered in the basic model.

System Composition of Drone Simulation Platforms

Multi-rotor drone simulation platforms typically consist of five main components: environment scene, sensors, drone model, flight controller, and interfaces. The environment scene provides the operational foundation for the entire simulation. It is the virtual venue where the drone模拟运行, generally comprising two main parts: a rendering engine and a physics engine. The rendering engine is primarily responsible for processing visual effects of the entire environment scene, including environmental elements and the moving drone within the scene. Currently, rendering engines or tools used in simulation platforms include Unity, Unreal Engine, OpenGL, etc. The drone’s motion state, collisions, etc., are computed and processed by the physics engine. The obtained drone motion state is fed into the rendering engine for processing. Physics engines used in existing simulation platforms mainly include PhysX, Bullet Physics, MuJoCo, etc.

Regarding sensors, different simulation platforms handle various sensors differently. Some directly use sensors provided in the environment scene, such as AirSim’s camera, which directly uses the readily available camera in Unreal Engine 4. Others first obtain relevant information from the environment scene and then process it further to achieve more realistic sensor data. For Inertial Measurement Unit (IMU) data processing, many simulation platforms add noise to the true value data obtained from the environment scene to make it closer to real IMU data. The relevant data information obtained from the sensor part is transmitted to the flight controller or called by the interface. Data passed into the flight controller assists in solving control commands.

The flight controller part’s main function is to solve the underlying control signals from the incoming control signals at different levels. The solved underlying signals, such as Pulse-width modulation (PWM) signals, are combined with the drone model and sent into the environment scene.

Finally, users access a series of predefined interfaces to control and operate the simulation platform. These interfaces are typically encapsulated as Python, C++ Application Programming Interfaces (APIs), establish communication with the Robot Operating System (ROS), or directly connect to various types of remote controls, etc. Users can diversely operate and control the drone, enabling the simulation platform to adapt to different operational and development needs.

Evaluation Methods for Multi-rotor Drone Simulation Platforms

Regarding the evaluation methods for multi-rotor drone simulation platforms, the authors of Flightmare summarized three elements of an excellent drone simulator: high-speed operation capability, accuracy of physical simulation, and high-quality image rendering. These three points have been continuously pursued by various drone simulation platforms. However, how to more holistically evaluate a multi-rotor drone simulation platform is discussed here. Overall, evaluating a multi-rotor drone simulation platform can consider its performance and functionality. Performance aspects can be divided into: physical accuracy, sensor realism, simulation running speed. Functionality aspects can be divided into: support for various sensors, extensibility and customization capability, multi-drone simulation capability, interface support capability, installation and deployment capability.

Performance aspects: Physical accuracy is crucial for a simulation platform. This is the significance of simulation. Good physical accuracy allows developers to preview their drone’s possible operational states in reality through simulation, thereby avoiding some dangerous or unreliable flight states. Sensor realism. With the continuous development of deep learning, more and more tasks employ deep learning methods. In deep learning methods, the quality of the dataset directly affects the performance of the trained model. The more realistic the sensor data from the simulation platform, the greater the possibility that deep learning algorithms trained in simulation can be directly transferred to reality. As sensor data becomes increasingly realistic, some research begins to adopt the method of collecting data from simulation environments. On one hand, this is because the realism presented by simulation platforms is recognized by researchers; on the other hand, it benefits from the convenience of data acquisition brought by simulation platforms, saving human and material costs. More importantly, simulation platforms can possess conditions difficult to achieve in reality, such as changes in weather conditions. Through simulation, datasets under different weather conditions can be easily obtained. Simulation running speed. While ensuring physical accuracy and image realism, optimizing running speed is particularly critical. Optimizing running speed will enhance the smoothness and coherence of the simulation process. With image quality and physical simulation accuracy remaining unchanged, it will significantly improve development efficiency. Furthermore, fast simulation operation provides richer datasets for machine learning solutions, which is of great value for improving algorithm training efficiency and quality. Fast and accurate simulation data can shorten the iteration cycle of machine learning models, thereby achieving higher learning levels in a shorter time.

Functionality aspects: Sensors in the simulation platform are an important part. Autonomous flight of multi-rotor drones relies on data detected by sensors. These data need to be processed to further provide control commands for autonomous flight. Therefore, the functional requirements should include support capability for sensors. Support capability for sensors includes not only the types of sensors supported but also the ability to adjust sensor parameters. Commonly used sensors like cameras, IMU, Global Positioning System (GPS), Light Detection and Ranging (LIDAR), optical flow, etc. Among them, IMU is indispensable for drones, so almost every drone simulation platform simulates IMU. Next is the camera. Cameras can play a role in multiple tasks such as target recognition and navigation positioning, so many simulation platforms support camera sensors, including RGB cameras, depth cameras, etc. In summary, support for various sensors can reflect the functional level of the simulation platform. Extensibility and customization capability. Simulated drone flight is a prior verification of actual flight, aimed at evaluating its flight performance and avoiding unnecessary losses. Therefore, providing corresponding simulation structures and dynamics models for different drone models is significant for improving simulation performance and algorithm transfer capability. In this regard, Isaac Gym and Gazebo allow users to import custom Unified Robot Description Format (URDF) files or Simulation Description Format (SDF) files, thereby achieving customized drone structure shapes and dynamic properties. Support for multi-drone simulation is also a key factor in measuring the functional level of a simulation platform. In reality, many tasks离不开多机. Multiple drones协同执行任务 can significantly improve task efficiency in many aspects. In the application field of multi-rotor drones, coordinated clusters of multiple drones have become an important research direction, such as swarm drones performing coordinated obstacle avoidance flight in complex environments like dense forests. However, in multi-drone cluster tasks, damage to one drone may affect the entire cluster task. Being able to simulate multi-drone clusters in a simulation platform and expose potential problems in multi-drone clusters in advance will greatly improve research and development efficiency. Support for multi-drones in a simulation platform reflects its parallel operation capability and interaction capability within the scene. Interface support capability. Drone simulation platforms provide a platform for simulation development. Their interaction with algorithms enables simulated autonomous drone flight. The more types of interfaces the simulation platform supports, the better its compatibility with algorithms, and the better the simulation results and actual flight results. In the debugging process of autonomous flight drones, some simulation platforms support software/hardware-in-the-loop (S/HITL) debugging, providing interfaces for communication with hardware. Introducing the flight controller used in actual flight during debugging makes simulation results closer to reality. On the other hand, increasingly more robot strategies revolve around reinforcement learning algorithms. In reinforcement learning, the gym environment interface proposed by OpenAI has become a template for environment interfaces. If such interfaces are supported at the simulation platform level, it will greatly improve the development efficiency of researchers for specific drone flight tasks. The installation and deployment capability of a multi-rotor drone simulation platform is a key indicator for evaluating its functionality. Simple and efficient installation and deployment of the simulation platform will lower the learning threshold for developers and researchers, helping them quickly engage in project or experimental development. Secondly, the installation and deployment efficiency of the simulation platform directly relates to its applicability in practical application scenarios. A simulation platform that can be easily integrated into existing workflows can effectively promote the coherence of the development process, testing, and algorithm verification. Furthermore, support for installation and deployment on local servers or cloud servers, transmitting the drone’s state to the client through communication protocols, operating the simulation platform online on the server, and controlling the simulation platform offline on the client to obtain results (videos, operational data, etc.), not only reduces the hardware burden on the client but also optimizes comprehensive client management.

Solutions for Multi-rotor Drone Flight Tasks

Existing drone solutions mainly include traditional solutions and learning-based solutions. In traditional solutions, flight navigation tasks are mostly divided into three parts: perception, planning, and control. These three parts cooperate to complete specific flight navigation tasks for multi-rotor drones.

The perception part is used to estimate the drone’s own pose state and other information, while also undertaking tasks such as recognition, detection, and exploration. Currently, a common method for perceiving the environment and obtaining the drone’s own pose in multi-rotor drones is Visual-Inertial Odometry (VIO), which processes environmental data acquired by cameras and IMU to obtain the drone’s own pose. This method has good performance in pose estimation while relatively low computational cost, making it a suitable choice for platforms with limited computational resources like drones. For example, VINS-Mono uses a single camera and low-cost inertial measurement unit to achieve high-precision positioning; ORB-SLAM3 supports reusing all previous information at all stages of the algorithm, improving positioning accuracy.

After obtaining pose information, the system plans the flight trajectory, such as polynomial-based trajectory planning, which performs 3rd or 4th order derivatives on the motion state, thus obtaining a smooth motion trajectory. Additionally, there is time-optimized trajectory planning, which considers how to adjust path parameters to obtain the fastest flight trajectory, thereby achieving the shortest time, so it is often used in racing tasks. Philipp Foehn et al. designed waypoint-based trajectory optimization to achieve the shortest time passing through preset waypoints. Furthermore, Chao Qin et al. additionally considered the shape of gate obstacles based on waypoints, generating a more reliable time-optimized trajectory. Trajectory planning is the middle环节 of the solution, taking the perception results from the previous step as its input, generating results that meet task requirements under constraints of dynamics, safety, and energy efficiency, and passing the results to the subsequent control part as input reference values. In complex flight tasks, efficient and reasonable trajectory planning is very important.

The control part refers to processing the trajectory given by planning, converting it into signals controlling drone flight, enabling the drone to track the trajectory well. It is mainly divided into linear controllers and nonlinear controllers: typical linear controllers include the PID control algorithm, which processes control signals proportionally, integrally, and differentially before input, to achieve the desired control state. The PID algorithm has good performance in most cases, but its parameter determination is often vague; typical nonlinear controllers include SE(3)-based geometric tracking control, model predictive control (MPC), etc. These control algorithms are based on the drone’s dynamics model, utilizing the model’s characteristics to achieve more precise control.

With the continuous development of machine learning, in recent years, more and more learning-based methods have been used to implement drone flight tasks, even surpassing traditional solutions in some aspects. Learning-based solutions use neural networks to replace one or several modules in the traditional solution’s perception, planning, and control, leveraging the strong expressive power of neural networks to accomplish more complex tasks. For example, Robert Penicka et al. implemented trajectory planning for drones flying in cluttered environments based on reinforcement learning and compared this method with traditional methods in four different environments, recording trajectory solution speed and trajectory flight time to measure trajectory effectiveness. The results showed that the learning method兼顾了解算速度和轨迹效果 (short flight time). Nina Wiedemann et al. used analytic policy gradient to propose a learning-based controller. This controller fully utilizes the gradients of parameters during learning, accelerating the training process while performing better than generally learning-based controllers. Compared with traditional methods, it shows a significant reduction in computation time, giving it development potential on platforms with limited computing power or high-maneuverability platforms. Yunlong Song et al. used deep reinforcement learning to achieve vision-based time-optimal control in cluttered environments. Through neural networks, they performed drone trajectory planning and control, achieving high computational efficiency while traversing cluttered environments.

More and more research shows that compared to traditional solutions, learning-based solutions have advantages in processing results and processing efficiency to varying degrees. To adapt to this development trend, drone simulation platforms, as an important part of the development process, are also constantly evolving, improving their own architecture, performance, and functionality to continuously meet the training and development needs of learning-based solutions, promoting innovation in drone technology and expansion of application fields.

Classification of Multi-rotor Drone Simulation Platforms

The classification of multi-rotor drone simulation platforms can be analyzed based on the current solutions for multi-rotor drone flight tasks, mainly divided into traditional solutions and learning-based solutions. Thus, simulation platforms are divided into two categories: traditional multi-rotor drone simulation platforms provide verification and deployment platforms for solutions, while learning-supportive simulation platforms provide training and learning platforms for learning-based solutions.

In traditional solutions, drone flight navigation tasks are typically decomposed into perception, planning, and control parts. Algorithms mostly improve the effectiveness and performance of these three parts, and simulation platforms have also made corresponding improvements based on these needs. For example, a major demand in the perception part is whether perception algorithms in the simulation platform can be reliably transferred to real environments. Some simulation platforms show emphasis on this, making sensor data simulation effects as close to reality as possible. On the other hand, the main demand in the control part stems from whether accurate dynamics models can be written to pursue flight effects close to reality. Some specific simulation platforms are developed with this goal.

In learning-based solutions, drones continuously interact and learn in the simulation platform, training a model applicable to specific flight tasks. Unlike traditional solutions that view the simulation platform as a verification platform for algorithms, in learning-based solutions, the characteristics of the simulation platform itself also affect the performance of the learned model. Therefore, besides having verification functions like traditional platforms, such simulation platforms also need to adapt to training and learning needs, such as high update rates required for large amounts of data, introduction of feedback from interactive tasks in the scene, etc.

In summary, multi-rotor drone simulation platforms are divided into two major categories based on the technical requirements and solution strategies of their flight tasks. Both types of simulation platforms have different focuses depending on the tasks. Traditional simulation platforms focus on algorithm verification and environment simulation, providing pre-development testing platforms for drone perception, planning, and control; while learning-supportive simulation platforms, through efficient data processing capabilities and interactive learning environments, provide effective途径 for model training of drone flight tasks. These two types of simulation platforms have their own focuses, jointly promoting the development and application of drone technology.

Case Studies and Characteristics of Multi-rotor Drone Simulation Platforms

The technology of simulation platforms in the multi-rotor drone field is developing rapidly. With technological progress, simulation platforms are continuously iterating and upgrading to adapt to new technical requirements. From initial simulation capability, to the pursuit of accurate dynamics, to high-fidelity images, and then to adapting to learning solutions, traditional solution-adapted simulation platforms are becoming mature while learning solution-adapted simulation platforms are developing rapidly.

According to the development of multi-rotor drone simulation platforms, typical simulation platforms include Gazebo, RotorS, AirSim, FlightGoggles, Flightmare, Isaac Gym, gym-pybullet-drones, RotorTM, etc., as well as Rflysim simulation platform developed by Feisi Lab jointly with Beihang University team, OmniDrones developed by Tsinghua University, and Fastsim developed by Zhejiang University Fast Lab.

Gazebo is a general-purpose robot simulation platform, widely used for simulating various robots, including wheeled robots, drones, soft robots. It supports modifying the simulated robot through URDF files or SDF files. Integration with ROS simplifies the migration process of software programs from simulation to real machines to some extent, making many robot-related tasks using ROS prioritize whether Gazebo can support simulation during development.

Table 2: Typical Drone Simulation Platforms
Platform/Software Release Time Supports Interactive Learning Environment Characteristics
Gazebo 2002 No General-purpose robot simulation platform, supports custom robot structures and partial dynamics, supports choice of physics engine, high threshold for simulation environment editing.
RotorS 2016 No Focuses on accurate dynamics of multi-rotor drones, based on Gazebo, used with ROS.
AirSim 2017 Yes High-fidelity rendered graphics, uses game engine, combined with UE4 has high simulation environment editability.
FlightGoggles 2019 No High-fidelity visual graphics, rich interface support, excellent graphics rendering performance, uses Unity game engine, supports hardware-in-the-loop simulation for simulation environments.
Flightmare 2020 Yes Excellent graphics rendering capability, introduces reinforcement learning-related interfaces, provides training environment for learning solutions.
RflySim 2021 No Supports FPGA hardware-in-the-loop simulation, has fine drone dynamics, uses Unreal Engine to provide high-fidelity 3D visual scenes, supports multi-drone cooperative simulation.
Isaac Gym 2021 Yes Developed by NVIDIA, suitable for reinforcement learning and robot research, utilizes GPU-accelerated parallel reinforcement learning training environment, where Aerial Gym is suitable for multi-rotor drones.
gym-pybullet-drones 2021 Yes Provides environment for multi-agent task learning solutions, focuses on multi-agent reinforcement learning.
RotorTM 2022 No Focuses on multi-rotor drone dynamics, developed dynamics for transport and payload tasks, supports multi-drone cooperative simulation.
OmniDrones 2023 Yes Reinforcement learning platform for drone control developed based on Isaac Sim, supports GPU-parallelized simulation, supports multi-agent reinforcement learning.

In terms of physical simulation, Gazebo supports switching between multiple high-performance physics engines. This choice allows robots to exhibit performance closer to reality in simulation based on needs. Regarding sensors, Gazebo provides plugin packages for simulating various sensors, covering LIDAR, RGB cameras, depth cameras, IMU, and many other commonly used robot sensors. The emergence of Gazebo promoted the development of robot simulation, proposing a large basic framework for robot simulation. It proposes various sensors and functions in the form of plugin packages, allowing developers to choose based on needs or develop customized functions required by themselves based on Gazebo and import them as new plugin packages. This framework led to many subsequent robot simulations in specific fields being developed more细化 based on Gazebo. RotorS is one such case for multi-rotor drone simulation. RotorS was developed by ETH Zurich’s Autonomous Systems Lab based on Gazebo’s framework, realizing multi-rotor drone simulation. This simulation platform constructs dynamics targeting rotors, making drone dynamics simulation relatively accurate and realistic. CrazyS added Bitcraze Crazyfile 2.0 micro drone model parameters based on RotorS, allowing the popular Crazyfile in research to have a convenient simulation platform. These simulation platforms initially enabled simulation for multi-rotor drones and pursued simulation realism to some extent. However, they still have some limitations, such as Gazebo’s lack of realism in graphics rendering, failing to achieve high-fidelity rendering like Unreal Engine or Unity, making it difficult to simulate some vision-based flight tasks in simulation, and not facilitating algorithm transfer from simulation to reality. On the other hand, RotorS and CrazyS simulation platforms do not support multi-drone simulation, making multi-drone tasks almost impossible to simulate here.

Due to the weakness in graphics rendering of Gazebo and simulators developed based on it, and the increasing number of vision-based application tasks, some multi-rotor drone simulation platforms focusing on visual graphics rendering emerged, among which AirSim is a typical representative. AirSim is a simulation platform including multi-rotor drones and autonomous driving developed by Microsoft. It has high-quality graphics rendering, can achieve photo-realistic levels, and can well adapt to vision-related flight tasks. Additionally, AirSim also provides hardware-in-the-loop simulation supporting real flight controllers and software-in-the-loop simulation of mainstream flight control programs, facilitating the deployment of simulation algorithms to real machines. Furthermore, AirSim benefits from the Unreal Engine community ecosystem,拥有大量可选择的高质量渲染场景、3D图形资产等, lowering the threshold for researchers in customizing visual tasks. At the same time, due to its combination with Unreal Engine, it has good editability. AirSim is widely used in autonomous drone racing, such as the drone race held at the 2019 NeurIPS conference. The emergence of AirSim gave multi-rotor drone simulation platforms good performance in visual effects, promoting the research and development of vision-related flight tasks. However, its high-quality rendering effect also意味着高硬件资源消耗, so some high-fidelity simulation scenes require higher-performance hardware to run, to keep the simulation running at a reasonable frame rate. Additionally, AirSim adopts a tight coupling approach in visual rendering and physical simulation. Although this approach can well match visual positions and physical simulation positions, it also limits the simulation running speed of AirSim. In the context of multi-rotor drones pursuing faster flight speeds, simulation running speed is receiving increasing attention. Therefore, FlightGoggles not only focuses on the quality of visual graphics rendering but also pays attention to simulation running speed. FlightGoggles is a drone simulation platform based on the Unity game engine developed by MIT. The realism in visual rendering also reaches photo-realistic levels. Although it still requires certain hardware resources, it separates the rendering pipeline from the drone’s physical simulation. Compared to AirSim, it enables the simulation platform to achieve higher running speeds. Furthermore, FlightGoggles uses a motion capture system to map the drone’s position in the real world to the virtual environment, while the real drone’s visual information comes from the virtual environment, introducing real hardware information more deeply in simulation mode, introducing real states to a greater extent into simulation in multi-rotor drone research and development. Algorithms developed based on this mode will be more robust, and transfer from simulation to reality will be more convenient.

Meanwhile, reinforcement learning technology has advanced, showing great potential for drone flight control. The University of Zurich developed Flightmare, a drone simulation platform suitable for reinforcement learning. Like FlightGoggles, it is based on the Unity game engine and decouples graphics rendering from the rotor drone’s dynamics model. To achieve high simulation running speeds, it also provides a set of standard interfaces matching OpenAI Gym, facilitating reinforcement learning development. Many drone flight tasks based on reinforcement learning use Flightmare for research and development. The emergence of Flightmare promoted the development of multi-rotor drones using reinforcement learning to achieve flight tasks. However, it is suitable for single-drone reinforcement learning training. For reinforcement learning training where multiple drones cooperate to complete flight tasks, gym-pybullet-drones launched a reinforcement learning training environment supporting multiple drones. It also has interfaces matching the OpenAI Gym standard. Some multi-agent reinforcement learning (MARL) research is based on this simulation platform. Isaac Gym is a general-purpose simulation platform supporting reinforcement learning training. It uses GPU to accelerate the reinforcement learning training process and can be used for reinforcement learning training of various robots like quadruped robots, humanoid robots, multi-rotor drones, where Aerial Gym is suitable for multi-rotor drone reinforcement learning training. Omni-Drones is built and developed based on Isaac Sim, also leveraging GPU’s parallel simulation capability, able to run efficiently, facilitating data collection during reinforcement learning training. Currently, this simulation platform mainly supports simulation development and verification of some flight control algorithms, showing weakness in meeting the needs of some visual tasks. The development team stated that they will introduce more complex tasks and scenes in the future.

Conclusion

With the continuous development of simulation technology, traditional multi-rotor drone simulation platforms are gradually maturing, playing an increasingly important role in drone technology research and development and testing. As key tools for drone research and development and testing, they provide a safe, economical, and highly controllable experimental platform for drone flight tasks, enabling research and development teams to conduct extensive algorithm testing and performance optimization on drones in simulated environments, reducing risks and costs that may arise in actual flight.

Meanwhile, with the increasing maturity of machine learning technology, learning-oriented drone simulation platforms are being widely used in the field of reinforcement learning. In reinforcement learning, drones learn strategies by interacting with the environment, and learning-oriented drone simulation platforms can provide such an interactive virtual environment, allowing drones to conduct a large amount of trial-and-error learning without contacting the real world. This not only greatly improves learning efficiency but also reduces experimental costs, especially in experimental scenarios involving high risks or high costs. These two types of simulation platforms have undergone varying degrees of optimization in dynamics, graphics rendering, etc., based on the flight tasks they need to complete.

Currently, multi-rotor drone simulation platforms still face some unresolved issues and challenges. Their development directions are展望 as follows:

(1) Standardized development of traditional multi-rotor drone simulation platforms. Although traditional multi-rotor drone simulation platforms are becoming mature, each simulation platform has its own standards and focuses. Different simulation platforms may have differences in modeling drones, leading to differences in simulation results using different simulation platforms. Therefore, it is necessary to establish standards for drone models to select appropriate models based on task focus.

(2) Systematic development of learning-supportive simulation platforms. Existing learning-supportive multi-rotor drone simulation platforms can already complete many flight tasks. Researchers have also realized the transfer of these learned results from simulation to reality. However, there is no complete system here that completely connects the learning solution from necessary data preparation to starting learning in the simulation platform to application deployment on actual drones. This aspect will be gradually improved during the widespread use of learning solutions.

(3) Unified integration and development of traditional multi-rotor drone simulation platforms and learning-supportive simulation platforms. Both have commonalities in construction, requiring building simulation environments, modeling multi-rotor drones, writing control interfaces, etc. The difference is that learning-supportive simulation platforms not only need to achieve algorithm verification but also support interaction with drones. Therefore, learning-supportive simulation platforms put forward higher performance requirements, requiring faster running speeds to achieve interactive data collection. However, existing simulation platforms have not yet fully solved this problem. For example, the rendering speed of realistic graphics does not meet the requirements of learning solutions, thus affecting the learning iteration of solutions.

Multi-rotor drone simulation platforms are at a crossroads of development, influenced by cutting-edge technologies such as deep reinforcement learning. The integration of these technologies marks the transition of multi-rotor drone simulation platforms from traditional algorithm verification to providing interactive learning environments. This transition not only broadens the application scope of simulation platforms, from basic flight dynamics simulation to autonomous decision-making learning in complex environments, but also greatly improves the intelligence level and adaptability of drone systems. Therefore, the development of multi-rotor drone simulation platforms will not only be of great significance for the advancement of drone technology but also explore new paths for the future intelligence and autonomy of drones.

Scroll to Top