Ignition Gazebo + SITL support

Reaching out to any developers interested in helping improve support running ArduPilot SITL with Ignition.

Current status

The ignition-edifice branch of ardupilot_gazebo is compatible with Ignition Edifice and uses the JSON interface to SITL. It is working for a variety of vehicle types (copter, plane, rover) but would definitely benefit from further testing.

Features:

  • Plugin supplies flight dynamics to SITL

Still to do:

  • Range finder sensors
  • GPS sensor
  • IR lock
  • Camera integration

The documentation on the main page still refers to the legacy Gazebo / SITL-Gazebo plugin. For details on installing and running with Ignition see this wiki entry: ArduPilot Ignition Gazebo

Models and environments

The ardupilot_gazebo repo includes a couple of vehicle models and worlds to help get started.

Iris quadcopter

Good for testing the installation and configuration is working. Can be run in an empty world.

Zephyr delta wing

The zephyr delta wing has been tested with ArduPilot plane4.1. The model has been configured differently to the example provided in SwiftGust’s fork and needs the gazebo-zephyr parameters to be modified (disable SERVO reversing for the elevons).

Feature rich environments

The Ignition team have published a number of feature rich environments that can be adapted for use with ArduPilot controlled models. This example shows the iris quadcopter interacting with the Ignition Edifice depot demo world.

And here we see that getting stuck in trees is not limited to RL.

Ignition is a good option for simulating rovers, and this environment is being used to develop the sensor support for the plugin.

Related work

This ArduPilot Issue: SITL Improvements #16531 includes a feature request for a 3D front end to native SITL models. The Ignition framework may provide a mechanism for this by using the ignition-physics library and plugin support. The idea is that ArduPilot would provide a physics plugin that adapts existing SITL models to ignition-gazebo. This approach should also allow collision logic to be added in the plugin. The ignition-physics TPE example contains most of the elements that would be required.

I’m currently putting together a POC to demonstrate this if anyone is interested in discussing.

4 Likes

thanks! Just trying this out. Some notes for the readme

  • needed rapidjson-dev installed
  • lock-step isn’t working correctly. If I stop ArduPilot in GDB then the copter falls out of the sky
  • I can load the Edifice depot world, but it isn’t clear how to add a vehicle to it (eg. the Iris)

Thanks for taking a look at this @tridge.

Usually you can drop models into a world using the Resource Spawner tool, however the edifice depot world available online is missing a system plugin for the imu sensor needed by AP. Here’s a version that includes the missing plugin and spawns the iris:

ardupilot_edifice_demo.sdf.zip (2.3 KB)

Extract it to the ardupilot_gazebo/worlds folder and start ignition with:

$ ign gazebo ardupilot_edifice_demo.sdf

The simulation can freeze up when placing a model into the world if it intersects with another object (usually the ground plane). This has to do with the physics engines settings for collisions - there will be velocity limiting in place to prevent very large forces. The default engine has changed in ignition from ode to dart and I’m not yet familiar with the new engines settings. Adjusting the model’s initial pose avoids the issue.

Let me look into this.

@tridge my code definitely does not try to lock step at the moment - it just lets the rest of the simulation skip ahead if nothing is received on the ArduPilot connection. I looked at the original Gazebo plugin code that this was ported from and it seems to have similar logic - there is a 1000 ms wait on the socket receive for data once a connection has been established, and a counter for the number of times the receive misses before declaring the connection broken, but there does not seem to be a block on the main Gazebo physics step if nothing comes back from ArduPilot. I’ll add the lock-step behaviour in (which I guess is to block the simulation until a JSON message with an incremented frame counter is received and report that the simulation is waiting for data) and add a parameter in the plugin XML that allows this to be toggled on and off.

1 Like

@tridge and @khancyr this is an initial attempt at lock-step support for Ignition with SITL-JSON.

I’ve not merged it into the main ignition-edifice branch because it’s a substantial reworking of the original ardupilot_gazebo plugin and I have yet to provide parameters to toggle between the lock-step mode and the previous behaviour (non lock-step).

There is performance degradation - about 50% down from the non lock-step version. It’s about at this point that a review from a UDP expert would be helpful to identify what to tweak in order to improve the simulation speed :wink:

Main result: vehicles no longer fall out of the sky when debug stepping ArduPilot:

ignition-gazebo_ardupilot-sitl_lock-step.2021-09-21 19_03_12

wow, it shouldn’t be any loss of performance. We’ll need some strace to work out why.

I wouldn’t rule out the possibility that I’ve done something daft when enforcing the lock-step. I’m adding the option now to enforce / not-enforce and that may uncover something.

Still not sure why my first attempt was running so poorly, but I’ve merged a version into the main ignition-edifice branch that runs as well as the original version without lock-step.

The example models for the iris and zephyr are now set up to use lock-step with the addition of an optional <lock_step>1<\lock_step> parameter. I’ve kept the default behaviour to be non-lock step for backwards compatibility.

I’ve also added the Ignition Edifice depot demo to the example worlds so it should run out of the box.

I have successfully started a mission (mode auto) with the Iris quadcopter using qGroundControl, but I wasn’t able with the Zephyr delta wing model. In this case I get from Ardupilot the message (Bad Launch Auto).
Could you show me, in more details, how I have to change the gazebo-zephyr parameters in Ardupilot.
Thanks in advance.
Marco