Plane: don't reset home on GPS startup on watchdog reset

This commit is contained in:
Peter Barker 2021-07-31 13:54:08 +10:00 committed by Andrew Tridgell
parent cd01069b88
commit 435988a300
1 changed files with 1 additions and 1 deletions

View File

@ -391,7 +391,7 @@ void Plane::update_GPS_10Hz(void)
if (current_loc.lat == 0 && current_loc.lng == 0) { if (current_loc.lat == 0 && current_loc.lng == 0) {
ground_start_count = 5; ground_start_count = 5;
} else { } else if (!hal.util->was_watchdog_reset()) {
if (!set_home_persistently(gps.location())) { if (!set_home_persistently(gps.location())) {
// silently ignore failure... // silently ignore failure...
} }