AP_Mission: save waypoint number for watchdog reset

This commit is contained in:
Andrew Tridgell 2019-05-09 19:23:35 +10:00
parent ebf04e70fe
commit 9173989e63
1 changed files with 3 additions and 0 deletions

View File

@ -223,6 +223,9 @@ void AP_Mission::update()
return;
}
// save persistent waypoint_num for watchdog restore
hal.util->persistent_data.waypoint_num = _nav_cmd.index;
// check if we have an active nav command
if (!_flags.nav_cmd_loaded || _nav_cmd.index == AP_MISSION_CMD_INDEX_NONE) {
// advance in mission if no active nav command