Gazebo is a real time physics simulator with many promising features for the simulation of the next generation of UAVs, self-aware of their environment.
As presented on previous posts, especially from the ASL team from ETH Zurich who interfaced PX4 with Gazebo, from Alexandr Buyval who posted the first interface for ArduCopter, or from Patrick Nolan, Gazebo offers the simulation of a variety of sensors. It includes models of ultrasound range finders, cameras, lidars, stereo cameras, etc. These combinations make Gazebo well suited to simulate indoor flights or close to obstacles.
Gazebo runs along ROS (Robot Operating System) which is a software framework containing libraries for message-passing, package management, visualizers, device drivers, etc.
This update fully restructures in "C++ the Ardupilot – ROS/Gazebo” plugin interface in order to bring out:
- an improved simulation stability and deterministic UAV response (step lock mechanism) ;
- a simplified ROS/Gazebo simulation launch, fully configurable through arguments to the well-used SITL launch script, sim_vehicle.sh ;
- integration of the GPS sensor provided by Hector's plugin ;
- the simulation of ArduPlane, with a Cessna model provided as an example for custom fixed-wing designs ;
- a georeferenced overlay map image on MavProxy, to better assess the UAV position relative to its simulated environment ;
- a new custom mode, Wall Follow, for precise distance control to vertical surfaces, as an example of new sensor use on Gazebo ;
- a safeguard parachute, releasable by the autopilot
With this update we hope the Ardupilot ROS/Gazebo SITL will have achieved a high enough stability and ease-of-use to become a common simulator for all phases of the engineering V-model:
- prototype new designs for specific applications, and virtually test various combinations of sensor payloads and flight modes before moving to real hardware ;
- debug in real-time Ardupilot, and even the communication between Ground Stations and the autopilot ;
- ultimately validate functions are well-behaved.
Besides conception usefulness, the ROS/Gazebo SITL simulator is also very helpful for new pilots to train on RC piloting, or for veterans to hone their skills in parameter tuning.
Next step would be to interface DroneAPI's code with ROS/Gazebo topic messages, as well as the simulation launch mechanism, to be able to run custom DroneAPI image processing codes over Gazebo camera frames. By achieving this, the SITL would close the loop of UAV system simulation.
In conclusion it is a great test bench for all the cool new functions and flight modes of the community!
All source codes are available on our Github:
https://github.com/AurelienRoy/ardupilot_sitl_gazebo_plugin
https://github.com/AurelienRoy/ardupilot/tree/wall_follow branch wall_follow
https://github.com/AurelienRoy/mavlink-gbp-release/tree/wall_follow branch wall_follow
https://github.com/AurelienRoy/MAVProxy/tree/map_overlay branch map_overlay
https://github.com/AurelienRoy/ardupilot_sitl_ros_tutorial.git
from InventUAV
------------------------------------------------------------------------------------------------------
Additional details:
The step lock mechanism enforces a pause of the Gazebo simulation until it receives the next motor command from Ardupilot. It then steps forward the simulation by 2.5 ms (for the 400 Hz update rate on Pixhawk hardware) and sends back new sensor measurements to Ardupilot. Unlike many controller simulations on Gazebo, Ardupilot is the master of the simulation clock.
This solution prevents Ardupilot from missing time steps when running on slow computers, thus improving the overall stability. Among other benefits, the debugging of Ardupilot is much easier: when its execution stops at a breakpoint, the simulation automatically stays on a standstill.
Among discomforts, in simulations with ground stations maps, you cannot properly assess the UAV position relative to its surroundings. This issue is now solved, at least for MavProxy, with the possibility to overlay a georeferenced map image. The image file path is specified as argument to MavProxy, by the SITL launch script, with the simulation start location defining the image's center geolocation.
Unfortunately the Gazebo orthographic projection camera, which would be much useful to create maps from screenshots, only arrives in Gazebo 6.0, with the Kinetic Kane ROS version (may 2016).
Parachute release :
In order to stress test safety mechanisms of Ardupilot, a parachute has been modeled and appears when the autopilot activates the release servo. This development leads the way for dynamic model insertion, which can be useful for special actions like saving a lost hiker with an accurate water bottle drop (UAV Outback Challenge 2014).
Wall-Follow Mode :
It is a new mode we conceived for our project's special needs.
It is an aiding system for pilots making close shots along a structure's surface. All commands are relative to a virtual wall plane, which is similar to the Simple mode. It combines a Loiter controller for the lateral axis (= parallel to the wall), and a distance controller on the forward axis (= toward the wall).
The pilot can freely control lateral movement (roll command), and height (throttle). The wall plane orientation is fixed as perpendicular to the UAV's yaw angle upon entering the mode, and the target distance is a parameter.
To maintain a good behavior even when facing surfaces with holes, or high granularity, the controller includes with a special filtering of frontal range measures, fully configurable through parameters. This way the UAV maintains a straight trajectory, despite gaps.
An equivalent wall-follow waypoint control is underway, for wall planes parallel to waypoint legs.
The development of this feature had to be rushed for the needs of the video. It has not yet been thoroughly tested, and any test on a real UAV should be performed with caution.
Comments
@NA I also experienced problem with controlling the yaw. I am using DO_CONDITION_YAW commands send via mavros (0.17). If I send the commands in the built-in simulation using ./sim_vehicle --console --map it works fine for Copter3.3.1 which is as far as I know at least the version Aurelien is using. Maybe we can figure out this issue together!
Does anybody else has problems controlling the yaw? Or are the others doing it?
I've been playing with this (the ArduCopter SITL Gazebo plugin) and am experiencing something weird with the yaw control. In modes where overriding the RC channel 4 is supposed to rotate the vehicle, nothing happens unless RC 4 is set to an extreme value (i.e. something close to 1000 or 2000) and in that case the vehicle just starts to wobble and eventually spiral into the ground. I did some debugging into the ArduCopter code and the yaw rates are getting passed in correctly, but I didn't dig any further than that because it doesn't look like these guys changed that much.
I'm already working from a clean and up to date version of your master branch.
How are you slowing down SITL sim? I added the following to Firmware/Tools/worlds/iris.world:
<physics type="ode">
<max_step_size>0.0001</max_step_size>
<real_time_factor>0.1000</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
and starting the simulation with:
make posix_sitl_default gazebo_iris
The copter quickly crashes. As mentioned, the vehicle is outputting heartbeats at the normal 1Hz.
The information you referenced is outdated. Here is a slowed down run:
Its reasonably new functionality, so I'm sure there is room left to tune. You should update from master, as I mentioned in my last post.
@PX4
How exact is slowing the PX4 SITL sim accomplished? When I slow down the physics in my gazebo world file, the copter loses control (and the SITL keeps pumping out heartbeats at the same rate).
This lead me to believe that slower than realtime is not supported:
https://groups.google.com/forum/#!topic/px4users/kFJM1uAHGwE
The PX4 SITL on master supports slowing / pausing the simulator. Please make sure to update if you experience issues with Gazebo.
@NA, there is a --speedup option to SITL binaries to choose the speed relative to realtime. If invoking via sim_vehicle.sh then it is the -S option.
It can be greater than or less than 1, for example:
sim_vehicle.sh -S 2
means 2x realtime. If you use -S 0.2 then it is 5x slower than realtime.
You can also attach a debugger and single step the code. That doesn't disturb the simulation.
@Andrew_Tridel and whoever else: Does the SITL backend always run in real time or can I clock it slower (i.e. if I slow down the real_time_update_rate in the gazebo physics so that the sim time runs slower than real time, will the SITL sim use the slowed down sim clock or the CPU clock to determine it's sampling interval). I know this doesn't currently work with the PX4 SITL sim.
@NA, the lock step scheduling in ArduPilot is not tied to 400Hz. In fact, the default SITL backends run at 1200Hz. You can run it at any speed greater than the loop speed of the autopilot (and it does not need to be a multiple of the loop speed).
If the gazebo setup uses 400Hz then that is probably because it uses the least CPU time. It should be possible to make it run at much higher speeds.
This step lock is a nice feature. Is the step length configurable, though? I'm trying to emulate a sensor that needs a simulation update faster than 2.5ms. Also, does this same mechanism control the ROS simulation time?