Browse Source

AP_Mission: save waypoint number for watchdog reset

master
Andrew Tridgell 6 years ago
parent
commit
9173989e63
  1. 3
      libraries/AP_Mission/AP_Mission.cpp

3
libraries/AP_Mission/AP_Mission.cpp

@ -223,6 +223,9 @@ void AP_Mission::update() @@ -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

Loading…
Cancel
Save