From 324200b52c309dccf457a719f87fa795e8bdc60f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 6 May 2013 13:32:11 +0900 Subject: [PATCH] Copter: disable centrifugal correction when disarmed --- ArduCopter/Parameters.pde | 4 ++-- ArduCopter/motors.pde | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 497d412739..aa779f1726 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -966,8 +966,8 @@ static void load_parameters(void) if (!ahrs.gps_gain.load()) { ahrs.gps_gain.set_and_save(1.0); } - // set gps_gain to zero, it will be set back to 1 as part of the arming process - ahrs.gps_gain.set(0); + // disable centrifugal force correction, it will be enabled as part of the arming process + ahrs.set_correct_centrifugal(false); // setup different AHRS gains for ArduCopter than the default // but allow users to override in their config diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index d061312378..634352bcc5 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -145,7 +145,7 @@ static void init_arm_motors() #endif // enable gps velocity based centrefugal force compensation - ahrs.gps_gain.load(); + ahrs.set_correct_centrifugal(true); // finally actually arm the motors motors.armed(true); @@ -214,7 +214,7 @@ static void init_disarm_motors() #endif // disable gps velocity based centrefugal force compensation - ahrs.gps_gain.set(0); + ahrs.set_correct_centrifugal(false); } /*****************************************