2018-12-14 13:36:32 -04:00
|
|
|
#!/bin/sh
|
|
|
|
#
|
|
|
|
# Omnibus F4SD specific board defaults
|
|
|
|
#------------------------------------------------------------------------------
|
|
|
|
|
|
|
|
|
2019-06-06 04:33:48 -03:00
|
|
|
# transition from LPE+Q to Q estimator (2019-06-05)
|
|
|
|
if param compare SYS_MC_EST_GROUP 1
|
|
|
|
then
|
|
|
|
param set SYS_MC_EST_GROUP 3
|
|
|
|
fi
|
|
|
|
|
2018-12-14 13:36:32 -04:00
|
|
|
|
|
|
|
if [ $AUTOCNF = yes ]
|
|
|
|
then
|
|
|
|
# Disable safety switch by default
|
|
|
|
param set CBRK_IO_SAFETY 22027
|
|
|
|
|
|
|
|
# use the Q attitude estimator, it works w/o mag or GPS.
|
2019-06-06 04:33:48 -03:00
|
|
|
param set SYS_MC_EST_GROUP 3
|
2018-12-14 13:36:32 -04:00
|
|
|
param set ATT_ACC_COMP 0
|
|
|
|
param set ATT_W_ACC 0.4000
|
|
|
|
param set ATT_W_GYRO_BIAS 0.0000
|
|
|
|
|
|
|
|
param set SYS_HAS_MAG 0
|
|
|
|
fi
|
|
|
|
|