1 ## SITL in gazebo 8 with ArduCopterPlugin
2 SITL (software in the loop) simulator allows you to run betaflight/cleanflight without any hardware.
3 Currently only tested on Ubuntu 16.04, x86_64, gcc (Ubuntu 5.4.0-6ubuntu1~16.04.4) 5.4.0 20160609.
6 see here: [Installation](http://gazebosim.org/tutorials?cat=install)
8 ### copy & modify world
10 `cp /usr/share/gazebo-8/worlds/iris_arducopter_demo.world .`
12 change `real_time_update_rate` in `iris_arducopter_demo.world`:
13 `<real_time_update_rate>0</real_time_update_rate>`
15 `<real_time_update_rate>100</real_time_update_rate>`
16 ***this suggest set to non-zero***
18 `100` mean what speed your computer should run in (Hz).
19 Faster computer can set to a higher rate.
20 see [here](http://gazebosim.org/tutorials?tut=modifying_world&cat=build_world#PhysicsProperties) for detail.
21 `max_step_size` should NOT higher than `0.0025` as I tested.
22 smaller mean more accurate, but need higher speed CPU to run as realtime.
25 run `make TARGET=SITL`
28 to avoid simulation speed slow down, suggest to set some settings belows:
30 In `configuration` page:
32 1. `ESC/Motor`: `PWM`, disable `Motor PWM speed Sparted from PID speed`
33 2. `PID loop frequency` as high as it can.
36 1. start betaflight: `./obj/main/betaflight_SITL.elf`
37 2. start gazebo: `gazebo --verbose ./iris_arducopter_demo.world`
38 4. connect your transmitter and fly/test, I used a app to send `MSP_SET_RAW_RC`, code available [here](https://github.com/cs8425/msp-controller).
41 betaflight -> gazebo `udp://127.0.0.1:9002`
42 gazebo -> betaflight `udp://127.0.0.1:9003`
44 UARTx will bind on `tcp://127.0.0.1:576x` when port been open.
46 `eeprom.bin`, size 8192 Byte, is for config saving.
47 size can be changed in `src/main/target/SITL/pg.ld` >> `__FLASH_CONFIG_Size`