Dual vtail_mini_talon Gazebo simulation behaves poorly

I am currently working on a Gazebo simulation using the vtail_mini_talon model. My goal is to run a simulation with two aircraft simultaneously, each controlled through separate ports, so that they can fly independently.

However, when I try to launch both aircraft:

  • They tend to crash or behave unpredictably immediately after takeoff.

  • It seems that control commands or topics conflict, even though I tried to assign separate ports.

  • I am using gz sim to start the simulation and standard ArduPilot SITL configurations for each aircraft.

I would like guidance on how to properly configure a multi-aircraft Gazebo environment so that each plane can be controlled independently without interference. Specifically:

  1. How to set up separate communication ports for each aircraft.

  2. How to launch multiple SITL instances in Gazebo correctly.

  3. Any example setups or best practices for running more than one aircraft at the same time.

Any help, advice, or example configurations would be greatly appreciated.

Thank you very much for your support.

Hello @Ahmet_Demir1, the behaviour described does seem like conflicting ports are being used by multiple instances of SITL. Have you managed to configure and run a standard SITL simulation using more than one vehicle (i.e. not using Gazebo, but just the simulator distributed with ArduPilot). There is documentation here: Using SITL — Dev documentation

If that works, then setting up multiple vehicles in Gazebo is similar - there are a number of ways to do this but for two vehicles the simplest is to create another copy of the model, rename it, and change the port number to increment by 10.

I’m currently looking into whether we can support many more vehicles in Gazebo using it’s ability to run one or more secondary physics engines when the world is divided into levels. It’s proving a bit tricky to set up, but if successful I plan to write a blog about the procedure.

Hello,

I have added the second aircraft to the Gazebo environment by creating a copy of the model and increasing its communication port by 10. The first aircraft connects and flies without issues. However, when I connect the second aircraft, the first one immediately falls.

I suspect the connections are interfering with each other, but I’m not sure how to properly configure them to run independently. I can share the SDF files for both aircraft so you can take a look. I would really appreciate your guidance on how to set up multiple aircraft in Gazebo without conflicts.

Thank you very much for your help.

<?xml version="1.0"?> <?xml version="1.0"?>

Have you managed to run multiple vehicles without Gazebo (standard SITL)?

No, I don’t know how it would be without using a gazebo.

Ok - I recommend reading through the dev wiki material on SITL linked above and getting that working first. It will probably resolve most of your issues.

I’ll try. I hope I succeed.

Thank you for the suggestion. I have tested it, and everything works fine without Gazebo using the following command:

sim_vehicle.py -v Plane --map --console --count 5 --auto-sysid --location CMAC --auto-offset-line 90,10 --mcast

However, this command uses the default Plane model, not the mini_talon_vtail. I haven’t added the mini_talon_vtail aircraft yet. Could you guide me on how to include mini_talon_vtail in the SITL simulation alongside the other planes?

Great! To run two Gazebo planes set --count 2 and add -f gazebo-zephyr --model json to the sim_vehicle.py option list.

The Gazebo world will need to include two zephyr models that have been named differently and with the ports set to 9002 and 9012 respectively.

Another way to include the models with different ports is to launch an empty world and load the sdf for the zephyr as a string, replace the port setting using string replace, then spawn the model using the gz-transport service bindings.

A am working on an example script for this as part of multi-vehicle support but it’s not published yet. As mentioned earlier for 2 vehicles it’s probably quicker to just copy the zephyr model, change the name and update the port.

fixed wing aircraft crash video


I copied the second plane, added it to the world file, changed the ports, but it still didn’t work.

@Ahmet_Demir1 - I’ve looked into this a little further and multi-zephyr sims in Gazebo are possible, but needed a little work.

plane-swarmx10_trim_480p

The following patches are needed:

The example is run using the following steps:

  • Make 10 copies of the zephyr_with_ardupilot model in ardupilot_gazebo and name the folders zephyr_with_ardupilot_1, zephyr_with_ardupilot_2, …, zephyr_with_ardupilot_10.

  • Edit each model and set <model name="zephyr_with_ardupilot_{n}"> etc.

  • Edit each model and set <fdm_port_in>90{n-1}2</fdm_port_in>

  • Edit the zephyr_runway.sdf world and add entries for each model:

    <include>
      <uri>model://zephyr_with_ardupilot_{n}</uri>
      <pose degrees="true">{2*(n - 1)} 0 0.422 -90 0 180</pose>
    </include>

Run Gazebo and check that the 10 planes are lined up along the x-axis

Start sim_vehicle.py

sim_vehicle.py --debug -v Plane -f gazebo-zephyr --model json --count 10 --auto-sysid --location CMAC --auto-offset-line 90,2 --console --map

Note the patches above will need to be applied to ardupilot and mavproxy first.

Once all the SITL instances have started (there will be 10 terminal windows, one for each SITL instance), adjust some parameters to make it easier to see the planes in a single screen.

For n = 1, … 10

vehicle {n}
param set WP_LOITER_RAD 20
param set RTL_ALTITUDE 10

Then

alllinks mode FBWA
alllinks arm throttle
alllinks rc 2 1600
alllinks rc 3 1800
alllinks mode rtl

This will arm and launch the planes in FBWA with a slight climb. The mode switch to RTL should put them in a loiter about home with a radius 20m