mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: raise accel arming threshold to 0.75
arming issues due to accel inconsistency are too common
This commit is contained in:
parent
18de1c2c47
commit
69cfe11455
@ -169,9 +169,9 @@ bool AP_Arming::ins_checks(bool report)
|
||||
// get next accel vector
|
||||
const Vector3f &accel_vec = ins.get_accel(i);
|
||||
Vector3f vec_diff = accel_vec - prime_accel_vec;
|
||||
// allow for up to 0.5 m/s/s difference. Has to pass
|
||||
// allow for up to 0.75 m/s/s difference. Has to pass
|
||||
// in last 10 seconds
|
||||
float threshold = 0.5f;
|
||||
float threshold = 0.75f;
|
||||
if (i >= 2) {
|
||||
/*
|
||||
we allow for a higher threshold for IMU3 as it
|
||||
|
Loading…
Reference in New Issue
Block a user