From 772a1acc379a63872c8789c4506979f6fead910c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 30 Apr 2015 15:52:32 +0900 Subject: [PATCH] Copter: cancel takeoff if mode changed --- ArduCopter/flight_mode.pde | 5 ++++- ArduCopter/takeoff.pde | 7 +++++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde index 8a1e70bafe..33d1c2bf13 100644 --- a/ArduCopter/flight_mode.pde +++ b/ArduCopter/flight_mode.pde @@ -234,7 +234,10 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) // this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in)); } - + + // cancel any takeoffs in progress + takeoff_stop(); + #if FRAME_CONFIG == HELI_FRAME // firmly reset the flybar passthrough to false when exiting acro mode. if (old_control_mode == ACRO) { diff --git a/ArduCopter/takeoff.pde b/ArduCopter/takeoff.pde index 2bcea7419e..91bcc590cf 100644 --- a/ArduCopter/takeoff.pde +++ b/ArduCopter/takeoff.pde @@ -61,6 +61,13 @@ static void takeoff_timer_start(float alt) takeoff_state.time_ms = (alt/takeoff_state.speed) * 1.0e3f; } +// stop takeoff +static void takeoff_stop() +{ + takeoff_state.running = false; + takeoff_state.start_ms = 0; +} + // update takeoff timer and stop the takeoff after time_ms has passed static void takeoff_timer_update() {