From 7d4c74c28e2d248b01375c8c68277d5e22c4e78a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 15 May 2014 16:11:17 +0900 Subject: [PATCH] Copter: when leaving AUTO only stop mission if running This resolves an issue in which the mission would not automatically start from the beginning if it had previously been run to completion --- ArduCopter/flight_mode.pde | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde index 2c274b56ca..db2fb54830 100644 --- a/ArduCopter/flight_mode.pde +++ b/ArduCopter/flight_mode.pde @@ -210,7 +210,9 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) // stop mission when we leave auto mode if (old_control_mode == AUTO) { - mission.stop(); + if (mission.state() == AP_Mission::MISSION_RUNNING) { + mission.stop(); + } } // smooth throttle transition when switching from manual to automatic flight modes