px4-firmware/posix-configs/rpi/px4_fw.config

35 lines
840 B
Plaintext

# navio config for FW
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
param set BAT_CNT_V_VOLT 0.001
param set BAT_V_DIV 10.9176300578
param set BAT_CNT_V_CURR 0.001
param set BAT_A_PER_V 15.391030303
dataman start
df_lsm9ds1_wrapper start -R 4
df_ms5611_wrapper start
navio_rgbled start
navio_adc 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
linux_pwm_out start -m ROMFS/px4fmu_common/mixers/AERT.main.mix
logger start -t -b 200
mavlink boot_complete