mirror of https://github.com/ArduPilot/ardupilot
Plane: don't reset home on GPS startup on watchdog reset
This commit is contained in:
parent
cd01069b88
commit
435988a300
|
@ -391,7 +391,7 @@ void Plane::update_GPS_10Hz(void)
|
|||
if (current_loc.lat == 0 && current_loc.lng == 0) {
|
||||
ground_start_count = 5;
|
||||
|
||||
} else {
|
||||
} else if (!hal.util->was_watchdog_reset()) {
|
||||
if (!set_home_persistently(gps.location())) {
|
||||
// silently ignore failure...
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue