From c7ba44db2dd96de7c363b0b2a09ad8258a7b187e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 4 Aug 2014 15:06:37 +0900 Subject: [PATCH] Copter: increase ekf check threshold for inav This increases the accel correction from 60cm/s to 80cm/s before the ekf check will trigger a land --- ArduCopter/ekf_check.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ekf_check.pde b/ArduCopter/ekf_check.pde index 1bb5dcfcb2..334754b344 100644 --- a/ArduCopter/ekf_check.pde +++ b/ArduCopter/ekf_check.pde @@ -12,7 +12,7 @@ #endif #ifndef EKF_CHECK_COMPASS_INAV_CONVERSION - # define EKF_CHECK_COMPASS_INAV_CONVERSION 0.01f // converts the inertial nav's acceleration corrections to a form that is comparable to the ekf variance + # define EKF_CHECK_COMPASS_INAV_CONVERSION 0.0075f // converts the inertial nav's acceleration corrections to a form that is comparable to the ekf variance #endif #ifndef EKF_CHECK_WARNING_TIME