SITL (software in the loop) simulator allows you to run betaflight/cleanflight without any hardware. Currently only tested on Ubuntu 16.04, x86_64, gcc (Ubuntu 5.4.0-6ubuntu1~16.04.4) 5.4.0 20160609.
see here: Installation
for Ubunutu 16.04:
cp /usr/share/gazebo-8/worlds/iris_arducopter_demo.world .
change real_time_update_rate
in iris_arducopter_demo.world
:
<real_time_update_rate>0</real_time_update_rate>
to
<real_time_update_rate>100</real_time_update_rate>
this suggest set to non-zero
100
mean what speed your computer should run in (Hz).
Faster computer can set to a higher rate.
see here for detail.
max_step_size
should NOT higher than 0.0025
as I tested.
smaller mean more accurate, but need higher speed CPU to run as realtime.
run make TARGET=SITL
to avoid simulation speed slow down, suggest to set some settings belows:
In configuration
page:
ESC/Motor
:PWM
, disableMotor PWM speed Sparted from PID speed
PID loop frequency
as high as it can.
- start betaflight:
./obj/main/betaflight_SITL.elf
- start gazebo:
gazebo --verbose ./iris_arducopter_demo.world
- connect your transmitter and fly/test, I used a app to send
MSP_SET_RAW_RC
, code available here.
betaflight -> gazebo udp://127.0.0.1:9002
gazebo -> betaflight udp://127.0.0.1:9003
UARTx will bind on tcp://127.0.0.1:576x
when port been open.
eeprom.bin
, size 8192 Byte, is for config saving.
size can be changed in src/main/target/SITL/pg.ld
>> __FLASH_CONFIG_Size