From 226e42f1d7f7a5e09c409f29dcd198eda7d167dd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 7 Aug 2014 21:43:33 +0900 Subject: [PATCH] Copter: rename EKF_CHECK_THRESH parameter --- ArduCopter/Parameters.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 355f084e01..0923d2548b 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -451,7 +451,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Description: Allows setting the maximum acceptable compass and velocity variance (0 to disable check) // @Values: 0:Disabled, 0.6:Default, 1.0:Relaxed // @User: Advanced - GSCALAR(ekfcheck_thresh, "EKFCHECK_THRESH", EKFCHECK_THRESHOLD_DEFAULT), + GSCALAR(ekfcheck_thresh, "EKF_CHECK_THRESH", EKFCHECK_THRESHOLD_DEFAULT), #if FRAME_CONFIG == HELI_FRAME // @Group: HS1_