mirror of https://github.com/ArduPilot/ardupilot
Copter: loosen accelerometer consistency check in z-axis
This commit is contained in:
parent
b1f204e2a6
commit
2c41459fe9
|
@ -216,6 +216,10 @@ bool Copter::pre_arm_checks(bool display_failure)
|
||||||
*/
|
*/
|
||||||
threshold *= 2;
|
threshold *= 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// EKF is less sensitive to Z-axis error
|
||||||
|
vec_diff.z *= 0.5f;
|
||||||
|
|
||||||
if (vec_diff.length() > threshold) {
|
if (vec_diff.length() > threshold) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
|
||||||
|
|
Loading…
Reference in New Issue