mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: GPS failsafe ensures LAND is pilot-controlled
This resolves issue #880 in which if a GPS failsafe occurred while the vehicle was already in LAND mode, the LAND would continue to be GPS controlled LAND instead of pilot-controlled LAND
This commit is contained in:
parent
2acddb9696
commit
4686eef266
@ -172,3 +172,11 @@ static bool update_land_detector()
|
|||||||
// return current state of landing
|
// return current state of landing
|
||||||
return ap.land_complete;
|
return ap.land_complete;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch
|
||||||
|
// called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS
|
||||||
|
// has no effect if we are not already in LAND mode
|
||||||
|
static bool land_do_not_use_GPS()
|
||||||
|
{
|
||||||
|
land_with_gps = false;
|
||||||
|
}
|
||||||
|
@ -215,6 +215,11 @@ static void failsafe_gps_check()
|
|||||||
set_mode(LAND);
|
set_mode(LAND);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// if flight mode is LAND ensure it's not the GPS controlled LAND
|
||||||
|
if (control_mode == LAND) {
|
||||||
|
land_do_not_use_GPS();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// failsafe_gps_off_event - actions to take when GPS contact is restored
|
// failsafe_gps_off_event - actions to take when GPS contact is restored
|
||||||
|
Loading…
Reference in New Issue
Block a user