This project presents a comprehensive three-stage approach to simulating and testing quadrotor (drone) behavior using the ArduPilot autopilot software stack. The first stage utilizes the Software-In-The-Loop (SITL) framework to emulate quadrotor dynamics without physical hardware. The second stage enhances realism by integrating SITL with the Gazebo simulator, allowing for 3D visualization and interaction using the Iris model. Finally, the third stage connects the simulation environment with ROS (Robot Operating System) via MAVROS, enabling ROS-based control and sensor integration. This simulation platform supports flight modes like Circle, RTL, AltHold, and Auto Mission Planning, offering a safe and extensible testbed for UAV development.
Autonomous aerial robots like quadrotors are widely used for inspection, mapping, and surveillance. Real-world testing is risky and expensive, especially during early development. SITL allows developers to simulate UAV behavior using the actual ArduPilot firmware stack in software.
This project includes three key phases:
The first phase of the project focuses on simulating UAV behavior using the SITL framework. SITL allows execution of the ArduCopter firmware in a fully virtual environment.
Figure: SITL-Based Simulation with ArduPilot Architecture
In this mode, the quadrotor spins in a circular path using throttle and radius parameters.
arm throttle (activate motors)
takeoff 50 (take-off the model upto 50cm height)
rc 3 1500 (set the motor speed to 1500rpm)
param set circle_radius 2000 (set the radius to 2000cm)
Figure: GeoFence Mode Setup with Boundary Constraints
In Auto Mode, the user defines a series of waypoints on the MAVProxy Map. The quadrotor autonomously follows the mission path after takeoff.
arm throttle (activate motors)
takeoff 20 (take-off the model up to 20cm height)
mode auto (switch to Auto mode to follow mission)
Figure: Mission Planning using MAVProxy Map
GeoFence Mode defines virtual boundaries in the airspace. The UAV stays within these boundaries and returns or lands if it tries to breach them.
arm throttle (activate motors)
takeoff 20 (take-off the model up to 20cm height)
mode auto (switch to Auto mode with GeoFence active)
Figure: GeoFence Mode Setup with Boundary Constraints
Enhancing the simulation by integrating Gazebo with SITL for real-time visual feedback using the Iris quadrotor model.
Figure: SITL + Gazebo Architecture Overview
To execute an autonomous mission, users can define waypoints directly on the MAVProxy Map:
Once the mission path is drawn, execute the following commands in the MAVProxy terminal to begin the autonomous flight:
arm throttle (activate motors)
takeoff 20 (take-off the model up to 20cm height)
mode auto (set to Auto mode to start mission execution)
Figure: Mission Planning using MAVProxy Map Interface
Until this point, the quadrotor simulation using SITL was controlled via the MAVProxy GCS terminal. The next phase of the project introduces integration with the Robot Operating System (ROS) to enable access to high-level robotics tools such as navigation stacks, perception pipelines, and planning algorithms.
MAVROS acts as a bridge between the MAVLink protocol (used by ArduPilot) and the ROS ecosystem. It translates MAVLink messages into ROS topics, enabling bi-directional communication between ArduPilot and ROS nodes. Additionally, MAVROS serves as a proxy interface for GCS commands and telemetry.
An open-source package named ardupilot_gazebo
(available on ROS wiki) provides the base for SITL-Gazebo-MAVROS integration. For this project:
iris
quadrotor model was extended by adding a camera and its Gazebo plugin.Figure: SITL + Gazebo Integrated with MAVROS for ROS Communication
This three-stage simulation project successfully demonstrates a scalable and modular approach to autonomous quadrotor testing using the ArduPilot ecosystem. The SITL and MAVProxy setup enabled safe emulation of flight behavior and mode switching without hardware. The Gazebo integration added rich 3D visualization for real-time observation and validation of UAV dynamics. Finally, the SITL + Gazebo + MAVROS interface bridged the system with the ROS ecosystem, enabling access to advanced autonomy tools, sensor integration, and future navigation algorithms. Together, this layered architecture provides a powerful testbed for developing, debugging, and validating UAV applications prior to real-world deployment.