Plane: Ignore low voltage failsafe during landing

Log it, but do not switch to RTL if already in final or landing.
This commit is contained in:
Andre Kjellstrup 2015-06-20 23:26:31 +02:00 committed by Andrew Tridgell
parent a5abb7c698
commit baf4989a80
1 changed files with 5 additions and 2 deletions

View File

@ -115,8 +115,11 @@ void Plane::low_battery_event(void)
}
gcs_send_text_fmt(PSTR("Low Battery %.2fV Used %.0f mAh"),
(double)battery.voltage(), (double)battery.current_total_mah());
if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
set_mode(RTL);
aparm.throttle_cruise.load();
}
failsafe.low_battery = true;
AP_Notify::flags.failsafe_battery = true;
}