Browse Source

ACM : removed 2-level DCM gain change - .1 will still be the default.

master
Jason Short 13 years ago
parent
commit
c81064279a
  1. 7
      ArduCopter/motors.pde

7
ArduCopter/motors.pde

@ -158,10 +158,6 @@ static void init_arm_motors() @@ -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() @@ -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;

Loading…
Cancel
Save