mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
ROVER: stop mission when leaving AUTO
This commit is contained in:
parent
1d70a337dd
commit
1bd863e36b
@ -273,9 +273,12 @@ void Rover::set_mode(enum mode mode)
|
||||
return;
|
||||
}
|
||||
|
||||
// If we are changing out of AUTO mode reset the loiter timer
|
||||
// If we are changing out of AUTO mode reset the loiter timer and stop current mission
|
||||
if (control_mode == AUTO) {
|
||||
loiter_start_time = 0;
|
||||
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
mission.stop();
|
||||
}
|
||||
}
|
||||
|
||||
control_mode = mode;
|
||||
|
Loading…
Reference in New Issue
Block a user