mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Mission: Prohibit resuming mission waypoints that are no longer in the mission
This commit is contained in:
parent
b57280125c
commit
7e5aa5bc4c
@ -92,9 +92,13 @@ void AP_Mission::resume()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// ensure cache coherence
|
// ensure cache coherence
|
||||||
// don't bother checking if the read is successful. If it fails _nav_cmd
|
if (!read_cmd_from_storage(_nav_cmd.index, _nav_cmd)) {
|
||||||
// won't change and we'll continue flying the old cached command.
|
// if we failed to read the command from storage, then the command may have
|
||||||
read_cmd_from_storage(_nav_cmd.index, _nav_cmd);
|
// been from a previously loaded mission it is illogical to ever resume
|
||||||
|
// flying to a command that has been excluded from the current mission
|
||||||
|
start();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// restart active navigation command. We run these on resume()
|
// restart active navigation command. We run these on resume()
|
||||||
// regardless of whether the mission was stopped, as we may be
|
// regardless of whether the mission was stopped, as we may be
|
||||||
|
Loading…
Reference in New Issue
Block a user