How to simulate a swarm of quadopters using ardupilot_sitl_gazebo_plugin?

Hi Everyone,

I am trying to simulate a group of UAVs using the ardupilot in gazebo. So far I have been able to actually bring up two different instances of the erlecopter in gazebo but I keep getting the same message:

ARI: Cannot receive input from Ardu, for the port is not open !

as for that I also show my launch file for two copters

<?xml version='1.0'?>
<launch>
 
   <!-- start world -->

  <arg name="simRate" default="nan"/>
  <!-- Enable simulation clock -->
  <param name="use_sim_time" type="bool" value="true" />

  
  <arg name="world_name" default="$(find multi_uav)/worlds/empty.world" />
  <arg name="gui" value="true" />
  <arg name="headless" value="false" /> 

  <env name="GAZEBO_MODEL_PATH" value="$(find ardupilot_sitl_gazebo_plugin)/meshes/meshes_sensors"/>

<!--<env name="GAZEBO_MODEL_PATH" value="$(find drcsim_model_resources)/gazebo_models/environments:$(find ardupilot_sitl_gazebo_plugin)/meshes/meshes_sensors:$(find ardupilot_sitl_gazebo_plugin)/meshes/meshes_outdoor:$(find ardupilot_sitl_gazebo_plugin)/meshes/meshes_warehouse"/>
-->
  
  
<group ns="uav">   

	<arg name="namespace" value="uav"/>	
	<arg name="enable_logging" default="true"/>
        <arg name="enable_ground_truth" default="true"/>
	<arg name="log_file" default="erlecopter1"/>
	<include file="$(find mavros)/launch/apm_sitl.launch" >
		<arg name="fcu_url" value="tcp://localhost:5760" />
		<arg name="gcs_url" value="udp://:14550@" /> 
		<arg name="tgt_system" value="1" />
		<arg name="tgt_component" value="1" /> 
	</include> 
  	<arg name="name" default="erlecopter1"/>
  	<arg name="model" default="$(find ardupilot_sitl_gazebo_plugin)/urdf/erlecopter_base.xacro"/>
  	<arg name="tf_prefix" default="$(arg namespace)"/>
  	<arg name="debug" default="true"/>
  	<arg name="verbose" default="true"/>



  <!-- Initial pose for the drone -->
  	<arg name="x" default="0.0"/> <!-- [m], positive to the North -->
  	<arg name="y" default="0.0"/> <!-- [m], negative to the East -->
  	<arg name="z" default="0.08"/> <!-- [m], positive Up -->
  	<arg name="roll" default="0"/> <!-- [rad] -->
  	<arg name="pitch" default="0"/> <!-- [rad] -->
  	<arg name="yaw" default="3.1415"/> <!-- [rad], negative clockwise -->

  <!-- send the robot XML to param server -->
  	<param name="robot_description" command="
    $(find xacro)/xacro --inorder '$(arg model)'
    enable_logging:=$(arg enable_logging)
    enable_ground_truth:=$(arg enable_ground_truth)
    log_file:=$(arg log_file)
    nspace:=$(arg namespace)"
  />
  	<param name="tf_prefix" type="string" value="$(arg tf_prefix)" />
	
	

  <!-- push robot_description to factory and spawn robot in gazebo -->
  	<node name="spawn_erlecopter" pkg="gazebo_ros" type="spawn_model"
   args="-param robot_description
         -urdf
         -x $(arg x)
         -y $(arg y)
         -z $(arg z)
         -R $(arg roll)
         -P $(arg pitch)
         -Y $(arg yaw)
         -model $(arg name)"
   respawn="false" output="screen" >
  	</node>	
	<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
	<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" output="screen"/>
</group> 

<group ns="uav2">   

	<arg name="namespace" value="uav2"/>	
	<arg name="enable_logging" default="true"/>
        <arg name="enable_ground_truth" default="true"/>
	<arg name="log_file" default="erlecopter1"/>
	<include file="$(find mavros)/launch/apm_sitl.launch" >
		<arg name="fcu_url" value="tcp://127.0.0.1:5770" />
		<arg name="gcs_url" value="udp://:14560@" /> 
		<arg name="tgt_system" value="1" />
		<arg name="tgt_component" value="1" /> 
	</include> 
  	<arg name="name" default="erlecopter2"/>
  	<arg name="model" default="$(find ardupilot_sitl_gazebo_plugin)/urdf/erlecopter_base.xacro"/>
  	<arg name="tf_prefix" default="$(arg namespace)"/>
  	<arg name="debug" default="true"/>
  	<arg name="verbose" default="true"/>



  <!-- Initial pose for the drone -->
  	<arg name="x" default="0.0"/> <!-- [m], positive to the North -->
  	<arg name="y" default="1.0"/> <!-- [m], negative to the East -->
  	<arg name="z" default="0.08"/> <!-- [m], positive Up -->
  	<arg name="roll" default="0"/> <!-- [rad] -->
  	<arg name="pitch" default="0"/> <!-- [rad] -->
  	<arg name="yaw" default="3.1415"/> <!-- [rad], negative clockwise -->

  <!-- send the robot XML to param server -->
  	<param name="robot_description" command="
    $(find xacro)/xacro --inorder '$(arg model)'
    enable_logging:=$(arg enable_logging)
    enable_ground_truth:=$(arg enable_ground_truth)
    log_file:=$(arg log_file)
    nspace:=$(arg namespace)"
  />
  	<param name="tf_prefix" type="string" value="$(arg tf_prefix)" />
	
	

  <!-- push robot_description to factory and spawn robot in gazebo -->
  	<node name="spawn_erlecopter" pkg="gazebo_ros" type="spawn_model"
   args="-param robot_description
         -urdf
         -x $(arg x)
         -y $(arg y)
         -z $(arg z)
         -R $(arg roll)
         -P $(arg pitch)
         -Y $(arg yaw)
         -model $(arg name)"
   respawn="false" output="screen" >
  	</node>	
	<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
	<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" output="screen"/>
</group> 

<include file="$(find multi_uav)/launch/empty_world.launch">
    <arg name="paused" value="true"/>  
    <arg name="headless" value="$(arg headless)"/>
    <arg name="gui" value="$(arg gui)"/>
    <arg name="world_name" value="$(arg world_name)"/>
  </include>

</launch>

I also should note that in the world file I’m doing (which I think might be the issue)

<plugin name="ardupilot_sitl_gazebo_plugin_1" filename="libardupilot_sitl_gazebo_plugin.so">
	<UAV_MODEL>uav/erlecopter</UAV_MODEL>
</plugin>

<plugin name="ardupilot_sitl_gazebo_plugin_2" filename="libardupilot_sitl_gazebo_plugin.so">
	<UAV_MODEL>uav2/erlecopter</UAV_MODEL>

I was hoping someone on this forum, could help me. I also upload two images of the corresponding mavproxy instances I have at startup

.

If you need any more details let me know (I’m running Ubuntu 16.04 LTS and ROS kinetic.

Thank you all very much,
Hugo

did you solve this problem?

is tcp://localhost:5760 and 5770 is the right address to configure?

There were a couple of things that needed to be changed:

the first was to make some changes to the ardupilot_gazebo_plugin

you can find these here:

inside each group tag you should call mavros as follows:

<include file="$(find mavros)/launch/apm_sitl.launch" >
	<arg name="fcu_url" value="udp://127.0.0.1:14551@" /> 
	<arg name="gcs_url" value="" /> 
	<arg name="tgt_system" value="1" />
	<arg name="tgt_component" value="1" /> 

changing the “51” to “61” for the second drone and adding +10 form that onward. Also in the world file, because the ports need to be specified, you should call it like

<plugin name="ardupilot_sitl_gazebo_plugin_1" filename="libardupilot_sitl_gazebo_plugin.so">
	<UAV_MODEL>uav/erlecopter</UAV_MODEL>	
<PORT_NO>9002</PORT_NO>
<PORT_OUT>9003</PORT_OUT>
</plugin> 

<plugin name="ardupilot_sitl_gazebo_plugin_2" filename="libardupilot_sitl_gazebo_plugin.so">
  <UAV_MODEL>uav2/erlecopter</UAV_MODEL> 
  <PORT_NO>9012</PORT_NO>
  <PORT_OUT>9013</PORT_OUT>
</plugin> 

adding +10 to each port with the increasing number of uavs. Also of note, I do not use the vehicle.sh, but the vehicle.py from the original ardupilot source here:

git://github.com/ArduPilot/ardupilot.git

hope this helps.

Cheers,
Hugo