I now want to run the simulation faster than real time, I managed to do so with a combination of –speedup X in sim_vehicle.py (is this the same as param set SIM_SPEEDUP X?) and <real_time_factor>0.0</real_time_factor> in the world .sdf
While this achieves FTRT performance for multiple vehicles, I think that the 1000Hz physics updates (as well as mavproxy) could be a CPU bottleneck.
What it the recommended, if any, way to reduce the frequency updates for ArduPilot SITL (I noted some of the pre-flight checks fail at lower frequencies)?
Hi @JaPan, the Gazebo time step can be increased to 0.001, but as you observer there may be some issues with the stability. A single vehicle instance should be able run at RTF > 1 on a suitable machine, but it will not be orders of magnitude faster. I don’t think mavproxy is a bottleneck as it does not dicate the simulation performance.
I’ve noticed in your repo that you have copied a number of the models from the ardupilot_gazebo and SITL_Models repos into your code baser but have removed the model.config files that contain author and copyright details and not provided any acknowledgment. This isn’t really acceptable. The ardupilot_gazebo repo is licensed under LGPL, so you are required to abide by the terms of the licence.
Thanks for the reply @rhys ! 0.001 is the timestep is I what I see in the example worlds from ardupilot_gazebo and it can run at RTF > 1 (but not by much, about 2, 3x in my case). At a first glance it seems it cannot be made any bigger, right? I was wondering if the 1000Hz is also a SITL-specific parameter (and in that case maybe it can be relaxed at the cost of some realism) or a minimum threshold for stability of the firmware itself (which is what I’m getting from your feedback).
[Let me just try to explain that the reason why you don’t see a model.config is because (to support multi-vehicle worlds) I generate multiple multiple models from one .sdf (where I added different sensors) programmatically (so the different model.configs that go into each folder are also generated in that shell). But I totally see your point so I will find a way to either re-instate that file or using everything dynamically from ardupilot_gazebo (which is also cloned “as-is” as a resource by my installation script anyway)]
[Let me just try to explain that the reason why you don’t see a model.config is because (to support multi-vehicle worlds)…
Hi @JaPan - all good, that makes sense. Better support for templating models in Gazebo would be a good addition. In the meanwhile it does require a certain amount of working around the lack of parameter support in SDF.
is this the same as param set SIM_SPEEDUP X ?
Essentially yes. The --speedup argument sets the parameter SIM_SPEEDUP in SITL (the terminal output shows the result of this).
I ran some quick tests using the zephyr model. The best rate I can get on a single vehicle before major instability is a RTF of about 13x using max_step_size 0.002 in the world SDF and setting SIM_SPEEDUP 15 after the vehicle has armed and launched. With 10 planes and similar settings that drops to around RTF 1x. This would suggest the Gazebo physics update is the limiter.
Thanks! That’s already very good, of course my setup will be slower because I run a number of extra tools for each drone (ROS, MAVROS, YOLO, simulated LiDAR) but it’s very useful to have a reference performance for 500Hz physics, I’ll do more tests with that (I thought I had some pre-arm warning at that rate but you’ve shown it’s flyable so I’ll investigate further).
(I thought I had some pre-arm warning at that rate but you’ve shown it’s flyable so I’ll investigate further).
That may be the case at high rates - the approach I use is to set SIM_SPEEDUP to 1 at startup, then increase the rate once the vehicle is armed and flying using the mavproxy param set SIM_SPEEDUP {x} command.
Just un update on this, I did manage run the Gazebo SITL simulation for iris and alti transition at ~8x real-time-factor with SIM_SPEEDUP of 10 (in a world with camera, lidar, and various collision shapes) with a 2ms Gazebo Sim timestep but I had to lower the SCHED_LOOP_RATE to 250 (from the default 500 and 300 of each model).