From df01d5acd7bbb030a98904206dbf1c7934767bf8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 18 Aug 2012 15:43:34 -0700 Subject: [PATCH] ACM : removed 2-level DCM gain change - .1 will still be the default. --- ArduCopter/motors.pde | 7 ------- 1 file changed, 7 deletions(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 5e4be63e58..937c14b5c5 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -158,10 +158,6 @@ static void init_arm_motors() // temp hack motor_light = true; digitalWrite(A_LED_PIN, LED_ON); - - // revert back to user default - ahrs._kp.load(); - ahrs._kp_yaw.load(); } @@ -177,9 +173,6 @@ static void init_disarm_motors() g.throttle_cruise.save(); - ahrs._kp.set(0.8); - ahrs._kp_yaw.set(0.8); - // we are not in the air takeoff_complete = false;