Browse Source

Copter: loosen accelerometer consistency check in z-axis

master
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
2c41459fe9
  1. 4
      ArduCopter/arming_checks.cpp

4
ArduCopter/arming_checks.cpp

@ -216,6 +216,10 @@ bool Copter::pre_arm_checks(bool display_failure) @@ -216,6 +216,10 @@ bool Copter::pre_arm_checks(bool display_failure)
*/
threshold *= 2;
}
// EKF is less sensitive to Z-axis error
vec_diff.z *= 0.5f;
if (vec_diff.length() > threshold) {
if (display_failure) {
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");

Loading…
Cancel
Save