Files
bizhang_-obav/posix-configs/rpi/px4_fw.config
Beat Küng 061bff14c8 rpi startup configs: set logger buffer size to 200
Avoid dropouts, we have enough RAM there.
2017-04-24 10:12:23 +02:00

29 lines
677 B
Plaintext

uorb start
param load
param set MAV_BROADCAST 1
#param set SYS_AUTOSTART 2104
param set MAV_TYPE 1
param set SYS_MC_EST_GROUP 2
dataman start
df_lsm9ds1_wrapper start -R 4
df_ms5611_wrapper start
navio_rgbled start
gps start -d /dev/spidev0.0 -i spi -p ubx
sensors start
commander start
navigator start
ekf2 start
fw_att_control start
fw_pos_control_l1 start
mavlink start -u 14556 -r 1000000
sleep 1
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
mavlink stream -u 14556 -s ATTITUDE -r 20
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
navio_sysfs_rc_in start
navio_sysfs_pwm_out start -m ROMFS/px4fmu_common/mixers/AERT.main.mix
logger start -t -b 200
mavlink boot_complete