Plane: ignore battery failsafe during landing

fixes https://github.com/ArduPilot/ardupilot/issues/10320
This commit is contained in:
Andrew Tridgell 2019-01-24 08:22:25 +11:00
parent ba53230f70
commit 69bf224730
1 changed files with 5 additions and 3 deletions

View File

@ -142,26 +142,28 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
{
switch ((Failsafe_Action)action) {
case Failsafe_Action_Land:
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != QLAND) {
// never stop a landing if we were already committed
if (plane.mission.jump_to_landing_sequence()) {
plane.set_mode(AUTO, MODE_REASON_UNKNOWN);
break;
}
}
}
FALLTHROUGH;
case Failsafe_Action_RTL:
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != QLAND ) {
// never stop a landing if we were already committed
set_mode(RTL, MODE_REASON_BATTERY_FAILSAFE);
aparm.throttle_cruise.load();
}
break;
case Failsafe_Action_Terminate:
char battery_type_str[17];
snprintf(battery_type_str, 17, "%s battery", type_str);
afs.gcs_terminate(true, battery_type_str);
break;
case Failsafe_Action_None:
// don't actually do anything, however we should still flag the system as having hit a failsafe
// and ensure all appropriate flags are going off to the user