AP_Mission: ensure cache coherence on mission resume
- when resuming a mission we should read the value from storage of the same index to ensure we're not continuing an old cached version of the mission item. - inherent problem: DO commands will continue and will be unaffected unless the new mission has a different DO_ command structure. If so, a set_current_cmd() or reset() should be issued by the GCS.
This commit is contained in:
parent
d4a34b3da1
commit
e6122d1a4e
@ -91,6 +91,11 @@ void AP_Mission::resume()
|
||||
}
|
||||
}
|
||||
|
||||
// ensure cache coherence
|
||||
// don't bother checking if the read is successful. If it fails _nav_cmd
|
||||
// won't change and we'll continue flying the old cached command.
|
||||
read_cmd_from_storage(_nav_cmd.index, _nav_cmd);
|
||||
|
||||
// restart active navigation command. We run these on resume()
|
||||
// regardless of whether the mission was stopped, as we may be
|
||||
// re-entering AUTO mode and the nav_cmd callback needs to be run
|
||||
|
Loading…
Reference in New Issue
Block a user