MAVROS +ardupilot +gazebo 无人机集群仿真 (一)
- 无人机仿真环境搭建
- 仿真软件安装
- 仿真环境测试
- 无人机多机仿真
- apm.launch文件修改
- 修改 iris_ardupilot.world
- 修改 iris_with_standoffs_demo1/demo2中的model.sdf
- 多机仿真测试
无人机仿真环境搭建
最近因为天气原因不能出去飞无人机完成实验,所以安心在ubuntu 上跑仿真,却没想到遇到这么多的问题。
仿真环境:
Ubuntu 18.04
ROS-melodic
Gazebo9
Mavros
ardupilot固件
ardupilot_gazebo
仿真软件安装
ubuntu 18.04双系统, ROS的安装以及mavros,ardupilot环境搭建网上教程已经很多了。此处省略。
仿真环境测试
仿真运行
第一个终端:
cd ardupilot/ArduCopter
…/Tools/autotest/sim_vehicle.py -f gazebo-iris --console --map
第二个终端:
gazebo --verbose iris_ardupilot.world
第三个终端:
进入mavros_ws的launch文件夹运行
roslaunch apm.launch
注:为了方便修改apm.launch,我在mavros_ws文件夹下新建了一个launch文件夹,将mavros原本的apm.launch文件复制了进去。
终端控制无人机起飞
mode guided
arm throttle
takeoff 2
无人机多机仿真
本来以为作无人机多机的仿真很方便的,没想到网上的资料少的可怜,仅有的一些例子还是px4的,借鉴着px4的多机仿真文件,搭建了apm的多机仿真。
apm.launch文件修改
<launch>
<!-- vim: set ft=xml noet : -->
<!-- example launch script for ArduPilot based FCU's -->
<arg name="gcs_url" default="" />
<arg name="tgt_component" default="1" />
<arg name="log_output" default="screen" />
<arg name="fcu_protocol" default="v2.0" />
<arg name="respawn_mavros" default="false" />
<group ns="uav0">
<!-- UAV0 -->
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="1"/>
<arg name="fcu_url" default="udp://127.0.0.1:14551@" />
<include file="$(find mavros)/launch/node.launch">
<arg name="pluginlists_yaml" value="$(find mavros)/launch/apm_pluginlists.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/apm_config.yaml" />
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg ID)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
<arg name="log_output" value="$(arg log_output)" />
<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
<arg name="respawn_mavros" value="$(arg respawn_mavros)" />
</include>
</group>
<group ns="uav1">
<!-- UAV1 -->
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="2"/>
<arg name="fcu_url" default="udp://127.0.0.1:14561@" />
<include file="$(find mavros)/launch/node.launch">
<arg name="pluginlists_yaml" value="$(find mavros)/launch/apm_pluginlists.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/apm_config.yaml" />
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg ID)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
<arg name="log_output" value="$(arg log_output)" />
<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
<arg name="respawn_mavros" value="$(arg respawn_mavros)" />
</include>
</group>
<group ns="uav2">
<!-- UAV2 -->
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="3"/>
<arg name="fcu_url" default="udp://127.0.0.1:14571@" />
<include file="$(find mavros)/launch/node.launch">
<arg name="pluginlists_yaml" value="$(find mavros)/launch/apm_pluginlists.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/apm_config.yaml" />
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg ID)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
<arg name="log_output" value="$(arg log_output)" />
<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
<arg name="respawn_mavros" value="$(arg respawn_mavros)" />
</include>
</group>
</launch>
<group ns="uav0">
给每个无人机的mavros一个组名,这样可以同时启动多个mavros节点和每个无人机单独连接,mavros的topic和service名称会相应变为 /uav0/mavros/…<arg name="fcu_url" default="udp://127.0.0.1:14551@" />
,mavros和仿真无人机的通信接口,运行sim_vehicle.py时会有显示。<arg name="ID" value="1"/>
每个无人机对应一个ID,与sim_vehicle.py中的sysid相对应,sim_vehicle.py在2020年10月的更新中加入了sysid这个属性,不然,还是无法将cmd或者set_mode通过mavros发送给仿真无人机。所以及时把自己的ardupilot库git pull一下。
修改 iris_ardupilot.world
- iris_ardupilot.world和 后面要修改的iris_with_standoffs_demo都在ardupilot_gazebo文件夹里面
将
<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>
增添为
<model name="iris_0">
<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>
<model name="iris_1">
<pose> 1 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo1</uri>
<pose> 1 0 0 0 0 0 </pose>
</include>
</model>
<model name="iris_2">
<pose> 2 0 0 0 0 0 </pose>
<include>
<uri>model://iris_with_standoffs_demo2</uri>
<pose> 2 0 0 0 0 0 </pose>
</include>
</model>
- 就是世界中原本只有一个无人机模型,现在增添了两个
- 注意的是
<uri>model://iris_with_standoffs_demo</uri>
<uri>model://iris_with_standoffs_demo1</uri>
<uri>model://iris_with_standoffs_demo2</uri>
这里用了3个不同的model,其实就是把第一个model复制粘贴了两遍,稍作修改后,改了一个名字,因为model里面定义了通信接口,所以需要三个不同的model区分不同的通信接口。
修改 iris_with_standoffs_demo1/demo2中的model.sdf
将
<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>
修改为
( iris_with_standoffs_demo1)
<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>
(iris_with_standoffs_demo2)
<plugin name="arducopter_plugin" filename="libArduPilotPlugin.so">
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9022</fdm_port_in>
<fdm_port_out>9023</fdm_port_out>
- 主要是修改
<fdm_port_in>9012</fdm_port_in>
和<fdm_port_in>9012</fdm_port_out>
后面运行三个sim_vehicle.py文件时,fdm_port_in会依次加10
多机仿真测试
终端一:sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 -I0 --sysid 1
终端二:sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 -I1 --sysid 2
终端三:sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 -I2 --sysid 3
终端四:gazebo --verbose iris_ardupilot.world
此时进入gazebo后应该是可以看到三个无人机的
终端五:roslaunch apm.launch
终端六:rostopic list
终端六里面应该可以看到/uav0,/uav1,/uav2的所有话题信息
后面我写了个ROS包控制,用键盘控制无人机起飞,后面再更新
放一张同时起飞的照片
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)