Plane: don't overwrite home on a armed watchdog reset

This commit is contained in:
Andrew Tridgell 2019-04-22 11:26:13 +10:00
parent bd6cd094c9
commit 645f758a15

View File

@ -139,6 +139,10 @@ void Plane::set_home_persistently(const Location &loc)
void Plane::set_home(const Location &loc)
{
if (hal.util->was_watchdog_armed()) {
// don't overwrite home
return;
}
ahrs.set_home(loc);
ahrs.Log_Write_Home_And_Origin();
gcs().send_home();