Browse Source

Copter: increased ESC auto-cal delay

master
Jason Short 10 years ago committed by Randy Mackay
parent
commit
3b5228922e
  1. 4
      ArduCopter/esc_calibration.pde

4
ArduCopter/esc_calibration.pde

@ -125,8 +125,8 @@ static void esc_calibration_auto() @@ -125,8 +125,8 @@ static void esc_calibration_auto()
delay(10);
}
// delay for 3 seconds
delay(3000);
// delay for 5 seconds
delay(5000);
// reduce throttle to minimum
motors.throttle_pass_through(g.rc_3.radio_min);

Loading…
Cancel
Save