mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-05 22:24:47 +08:00
commander: update EKF accel & gyro bias arming limits
- these should have been rescaled when the ecl/EKF filter update period changed from 8 ms -> 10 ms
This commit is contained in:
@@ -569,7 +569,7 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f);
|
||||
* @decimal 4
|
||||
* @increment 0.0001
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 1.73e-3f);
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 0.0022f);
|
||||
|
||||
/**
|
||||
* Maximum value of EKF gyro delta angle bias estimate that will allow arming
|
||||
@@ -578,10 +578,10 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 1.73e-3f);
|
||||
* @unit rad
|
||||
* @min 0.0001
|
||||
* @max 0.0017
|
||||
* @decimal 5
|
||||
* @decimal 4
|
||||
* @increment 0.0001
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_EKF_GB, 8.7e-4f);
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_EKF_GB, 0.0011f);
|
||||
|
||||
/**
|
||||
* Maximum accelerometer inconsistency between IMU units that will allow arming
|
||||
|
||||
Reference in New Issue
Block a user