Browse Source

PLane: support Loiter to Qland battery failsafe action

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
682798d044
  1. 5
      ArduPlane/Plane.h
  2. 9
      ArduPlane/events.cpp

5
ArduPlane/Plane.h

@ -1129,7 +1129,10 @@ private: @@ -1129,7 +1129,10 @@ private:
#if HAL_QUADPLANE_ENABLED
Failsafe_Action_QLand = 4,
#endif
Failsafe_Action_Parachute = 5
Failsafe_Action_Parachute = 5,
#if HAL_QUADPLANE_ENABLED
Failsafe_Action_Loiter_alt_QLand = 6,
#endif
};
// list of priorities, highest priority first

9
ArduPlane/events.cpp

@ -203,13 +203,20 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) @@ -203,13 +203,20 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
{
switch ((Failsafe_Action)action) {
#if HAL_QUADPLANE_ENABLED
case Failsafe_Action_Loiter_alt_QLand:
if (quadplane.available()) {
plane.set_mode(mode_lotier_qland, ModeReason::BATTERY_FAILSAFE);
break;
}
FALLTHROUGH;
case Failsafe_Action_QLand:
if (quadplane.available()) {
plane.set_mode(mode_qland, ModeReason::BATTERY_FAILSAFE);
break;
}
FALLTHROUGH;
#endif
#endif // HAL_QUADPLANE_ENABLED
case Failsafe_Action_Land: {
bool already_landing = flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND;
#if HAL_QUADPLANE_ENABLED

Loading…
Cancel
Save