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
This commit is contained in:
Randy Mackay 2014-05-15 16:11:17 +09:00
parent 5d20594fa4
commit 7d4c74c28e
1 changed files with 3 additions and 1 deletions

View File

@ -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