AP_Arming: loosen accelerometer consistency check on Z axis
Original author @jschall via 88f5d9f858
This commit is contained in:
parent
d55050e5e3
commit
0281b948df
@ -210,6 +210,9 @@ bool AP_Arming::ins_checks(bool report)
|
||||
*/
|
||||
threshold *= 3;
|
||||
}
|
||||
// EKF is less sensitive to Z-axis error and Z-axis is more
|
||||
// likely to be temperature-sensitive on our hardware
|
||||
vec_diff.z *= 0.5f;
|
||||
if (vec_diff.length() <= threshold) {
|
||||
last_accel_pass_ms[i] = AP_HAL::millis();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user