# Multi-UAV Gazebo Simulation
Tutorial for Multi-UAV (Quadcopters) simulation in Gazebo and Ardupilot.
# Installation
# Ubuntu
Ubuntu 20.04 inside a Virtual Machine (VM) used in this tutorial.
# Gazebo
The Gazebo version 11 is used in this tutorial. ROS noetic has gazebo11 but if there is problem with it, you can use steps below to install it:
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' | |
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add – | |
sudo apt-get update | |
sudo apt-get install gazebo11 libgazebo11-dev |
If you are using Ubuntu in a VM and gazebo has graphical problems, put the line below inside your bash (bashrc, zshrc, …):
export SVGA_VGPU10=0 |
# Ardupilot
The latest version (4.3.6 at the time of writing) used in this tutorial. You can use steps below to install it:
git clone https://github.com/ArduPilot/ardupilot.git | |
cd ardupilot | |
git submodule update --init –recursive | |
alias waf="$PWD/modules/waf/waf-light" | |
waf configure --board=sitl | |
waf all | |
./Tools/environment_install/install-prereqs-ubuntu.sh -y |
# Ardupilot_gazebo
git clone https://github.com/SwiftGust/ardupilot_gazebo | |
cd ardupilot_gazebo | |
mkdir build | |
cd build | |
cmake .. | |
make -j2 | |
sudo make install |
After installation of this plugin, you need to add lines below inside your bash (bashrc, zshrc, …):
source /usr/share/gazebo/setup.sh | |
export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models:${GAZEBO_MODEL_PATH} | |
export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models_gazebo:${GAZEBO_MODEL_PATH} | |
export GAZEBO_RESOURCE_PATH=~/ardupilot_gazebo/worlds:${GAZEBO_RESOURCE_PATH} | |
export GAZEBO_PLUGIN_PATH=~/ardupilot_gazebo/build:${GAZEBO_PLUGIN_PATH} |
# Run single UAV
- Open a terminal and run the commands below:
cd ~/ardupilot/Tools/autotest | |
./sim_vehicle.py -v ArduCopter -f gazebo-iris --console -I0 |
- Open a new terminal and run:
gazebo --verbose ~/ardupilot_gazebo/worlds/iris_ardupilot.world |
- After seeing “APM: EKF2 IMU0 is using GPS” message in console, you can use the commands below in the first terminal for takeoff test:
mode guided | |
arm throttle | |
takeoff 5 |
# Run multiple UAVs
- For any number of UAVs that you want to simulate, make a copy of “iris_with_standoffs_demo” from ardupliot_gazebo/models folder (iris_with_standoffs_demo_1, iris_with_standoffs_demo_2, iris_with_standoffs_demo_3, …).Besides,you need to add these folders to /.gazebo folder.
- Open “model.sdf” file inside of each iris_with_standoffs_demo folder and change <fdm_port_in> and <fdm_port_out> under plugin name=“arducopter_plugin” tag. For example for the first UAV (iris_with_standoffs_demo_1) use below:
<plugin name="arducopter_plugin" filename="libArduPilotPlugin.so"> | |
<fdm_addr>127.0.0.1</fdm_addr> | |
<fdm_port_in>9002</fdm_port_in> | |
<fdm_port_out>9003</fdm_port_out> |
- For second UAV (iris_with_standoffs_demo_2) use below:
<plugin name="arducopter_plugin" filename="libArduPilotPlugin.so"> | |
<fdm_addr>127.0.0.1</fdm_addr> | |
<fdm_port_in>9012</fdm_port_in> | |
<fdm_port_out>9013</fdm_port_out> |
-
And so on for each UAV add “10” to each port (9002-9003, 9012-9013, 9022-9023, 9032-9033, …).
-
Now make a copy of iris_ardupilot.world from ardupilot_gazebo/worlds folder:
cd ~/ardupilot_gazebo/worlds | |
cp iris_ardupilot.world iris_multiuav.world |
- Open the new iris_multiuav.world file and change the bottom of file from this:
<model name="iris"> | |
<pose> 0 0 0 0 0 0 </pose> | |
<include> | |
<uri>model://iris_with_standoffs_demo</uri> | |
<pose> 0 0 0 0 0 0 </pose> | |
</include> | |
</model> |
- To this (this is for 4 UAV example):
<model name="iris_demo_1"> | |
<pose> 0 0 0 0 0 0 0 </pose> | |
<include> | |
<uri>model://iris_with_standoffs_demo_1</uri> | |
</include> | |
</model> | |
<model name="iris_demo_2"> | |
<pose> -10 -10 0 0 0 0 0 </pose> | |
<include> | |
<uri>model://iris_with_standoffs_demo_2</uri> | |
</include> | |
</model> | |
<model name="iris_demo_3"> | |
<pose> -20 0 0 0 0 0 0 </pose> | |
<include> | |
<uri>model://iris_with_standoffs_demo_3</uri> | |
</include> | |
</model> | |
<model name="iris_demo_4"> | |
<pose> -10 10 0 0 0 0 0 </pose> | |
<include> | |
<uri>model://iris_with_standoffs_demo_4</uri> | |
</include> | |
</model> |
- Open a terminal for each UAV and run the commands below in each of them (4 UAV example):
# First terminal: | |
cd ~/ardupilot1/Tools/autotest | |
./sim_vehicle.py -v ArduCopter -f gazebo-iris --console -I0 | |
# Second terminal: | |
cd ~/ardupilot1/Tools/autotest | |
./sim_vehicle.py -v ArduCopter -f gazebo-iris --console -I1 | |
# Third terminal: | |
cd ~/ardupilot1/Tools/autotest | |
./sim_vehicle.py -v ArduCopter -f gazebo-iris --console -I2 | |
# Fourth terminal: | |
cd ~/ardupilot1/Tools/autotest | |
./sim_vehicle.py -v ArduCopter -f gazebo-iris --console -I3 |
- Open a new terminal and run the command below:
gazebo --verbose ~/ardupilot_gazebo/worlds/iris_multiuav.world |
- Wait for each UAV to get “APM: EKF2 IMU0 is using GPS” message and then you can control UAVs.
附件:
Ardupilot_gazebo 架构图
flowchart TB | |
subgraph "Gazebo仿真环境" | |
GW["Gazebo世界"] --- GP["物理引擎\n(ODE/Bullet)"] | |
GP --- Models["车辆/传感器模型"] | |
Models --- GPlugin["ArduPilot\nGazebo插件"] | |
end | |
subgraph "ArduPilot SITL" | |
FC["飞控代码"] --- AP["ArduPilot核心"] | |
AP --- Protocols["通信协议\n(MAVLink)"] | |
end | |
subgraph "通信层" | |
Socket["UDP Socket\n端口连接"] | |
end | |
GPlugin <--> Socket | |
Protocols <--> Socket | |
subgraph "地面站" | |
GCS["Mission Planner/\nQGroundControl"] | |
end | |
Protocols <--> GCS | |
subgraph "用户界面/工具" | |
Tools["开发工具\n监控界面"] | |
end | |
GCS --- Tools |
flowchart TB | |
classDef ardupilotComponents fill:#f9d5e5,stroke:#333,stroke-width:1px | |
classDef gazeboComponents fill:#d5f9e5,stroke:#333,stroke-width:1px | |
classDef communicationComponents fill:#e5d5f9,stroke:#333,stroke-width:1px | |
classDef userComponents fill:#f9e5d5,stroke:#333,stroke-width:1px | |
%% ArduPilot SITL 详细组件 | |
subgraph ARDUPILOT["ArduPilot SITL系统"] | |
direction TB | |
SITL_CORE["SITL核心模拟器"] | |
AP_FW["ArduPilot固件\n(Copter/Plane/Rover/Sub)"] | |
AHRS["姿态航向参考系统\n(AHRS)"] | |
EKF["扩展卡尔曼滤波器\n(EKF2/EKF3)"] | |
CONTROL["控制系统\n(PID/姿态控制器/位置控制器)"] | |
NAV["导航系统\n(航路点/任务规划)"] | |
MAVLIB["MAVLink库"] | |
COMM_DRIVERS["通信驱动\n(UART/UDP/TCP)"] | |
PARAM["参数系统"] | |
FENCE["地理围栏"] | |
VEHICLE_CODE["车辆特定代码"] | |
LOG["数据记录系统"] | |
SITL_CORE --> AP_FW | |
AP_FW --> AHRS & EKF & CONTROL & NAV & PARAM & FENCE & VEHICLE_CODE & LOG | |
AHRS --> EKF | |
EKF --> CONTROL | |
CONTROL --> NAV | |
AP_FW --> MAVLIB --> COMM_DRIVERS | |
end | |
%% Gazebo 详细组件 | |
subgraph GAZEBO["Gazebo仿真环境"] | |
direction TB | |
WORLD["世界模型\n(.world文件)"] | |
PHYSICS["物理引擎\n(ODE/Bullet/Simbody/DART)"] | |
MODELS["模型定义\n(.sdf/.urdf文件)"] | |
SENSORS["传感器模型\n(IMU/GPS/气压计/相机/雷达)"] | |
PLUGIN_LOADER["插件加载器"] | |
RENDERING["图形渲染引擎"] | |
DYNAMICS["动力学计算"] | |
COLLISIONS["碰撞检测"] | |
ENV_EFFECTS["环境效应\n(风/湍流/降水)"] | |
WORLD --> PHYSICS & MODELS & ENV_EFFECTS | |
MODELS --> SENSORS | |
PHYSICS --> DYNAMICS & COLLISIONS | |
MODELS --> PLUGIN_LOADER | |
WORLD --> RENDERING | |
end | |
%% 通信与中间层 | |
subgraph COMM["通信层"] | |
direction TB | |
UDP["UDP套接字\n(端口14550-14557)"] | |
FDMSOCKET["FDM Socket\n(物理动态模型接口)"] | |
SIM_SOCKET["仿真控制Socket"] | |
MAVPROXY["MAVProxy\n(MAVLink代理)"] | |
UDP <--> MAVPROXY | |
FDMSOCKET <--> SIM_SOCKET | |
end | |
%% ArduPilot Gazebo 插件详情 | |
subgraph PLUGIN["ArduPilot Gazebo插件"] | |
direction TB | |
PLUGIN_INIT["插件初始化"] | |
MODEL_INTERFACE["模型接口"] | |
SENSOR_UPDATE["传感器数据更新"] | |
ACTUATOR["执行器命令处理"] | |
SIM_STATE["仿真状态管理"] | |
POS_ROT["位置/旋转计算"] | |
FORCE_TORQUE["力和力矩应用"] | |
PLUGIN_INIT --> MODEL_INTERFACE | |
MODEL_INTERFACE --> SENSOR_UPDATE & ACTUATOR | |
ACTUATOR --> FORCE_TORQUE | |
SENSOR_UPDATE --> POS_ROT | |
POS_ROT & FORCE_TORQUE --> SIM_STATE | |
end | |
%% 用户接口组件 | |
subgraph USER["用户接口系统"] | |
direction TB | |
GCS["地面站\n(Mission Planner/QGC)"] | |
MAVLINK_INSPECTOR["MAVLink检查器"] | |
PLOT["实时数据绘图"] | |
JOYSTICK["摇杆控制"] | |
HMI["人机交互界面"] | |
GCS --> MAVLINK_INSPECTOR & PLOT & JOYSTICK | |
MAVLINK_INSPECTOR & PLOT & JOYSTICK --> HMI | |
end | |
%% 数据流路线 | |
%% 从 Gazebo 到 ArduPilot 的传感器数据流 | |
SENSORS --> PLUGIN::SENSOR_UPDATE | |
PLUGIN::POS_ROT --> FDMSOCKET | |
FDMSOCKET --> SITL_CORE | |
%% 从 ArduPilot 到 Gazebo 的控制命令流 | |
CONTROL --> COMM_DRIVERS | |
COMM_DRIVERS --> SIM_SOCKET | |
SIM_SOCKET --> PLUGIN::ACTUATOR | |
PLUGIN::FORCE_TORQUE --> PHYSICS | |
%% MAVLink 通信流 | |
MAVLIB --> UDP | |
UDP --> MAVPROXY | |
MAVPROXY --> GCS | |
%% 配置和初始化流 | |
PARAM --> SITL_CORE | |
PLUGIN_LOADER --> PLUGIN::PLUGIN_INIT | |
%% 应用样式 | |
class ARDUPILOT,AP_FW,AHRS,EKF,CONTROL,NAV,MAVLIB,COMM_DRIVERS,PARAM,FENCE,VEHICLE_CODE,LOG,SITL_CORE ardupilotComponents | |
class GAZEBO,WORLD,PHYSICS,MODELS,SENSORS,PLUGIN_LOADER,RENDERING,DYNAMICS,COLLISIONS,ENV_EFFECTS gazeboComponents | |
class COMM,UDP,FDMSOCKET,SIM_SOCKET,MAVPROXY,PLUGIN,PLUGIN_INIT,MODEL_INTERFACE,SENSOR_UPDATE,ACTUATOR,SIM_STATE,POS_ROT,FORCE_TORQUE communicationComponents | |
class USER,GCS,MAVLINK_INSPECTOR,PLOT,JOYSTICK,HMI userComponents |