AP_Arming: loosen accelerometer consistency check on Z axis

Original author @jschall via 88f5d9f858
This commit is contained in:
Jonathan Challinger 2016-04-18 13:36:17 -07:00 committed by Tom Pittenger
parent d55050e5e3
commit 0281b948df

View File

@ -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();
}