From 4068d57930fa329eafa218b94f803e08c237d5d1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 4 Feb 2022 14:24:05 +1100 Subject: [PATCH] Plane: correct spelling of mode_lotier_qland --- ArduPlane/Plane.h | 4 +--- ArduPlane/control_modes.cpp | 2 +- ArduPlane/events.cpp | 6 +++--- 3 files changed, 5 insertions(+), 7 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index bb1bb8661c..d8f87eb29d 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -280,6 +280,7 @@ private: ModeQLand mode_qland; ModeQRTL mode_qrtl; ModeQAcro mode_qacro; + ModeLoiterAltQLand mode_loiter_qland; #if QAUTOTUNE_ENABLED ModeQAutotune mode_qautotune; #endif // QAUTOTUNE_ENABLED @@ -288,9 +289,6 @@ private: #if HAL_SOARING_ENABLED ModeThermal mode_thermal; #endif -#if HAL_QUADPLANE_ENABLED - ModeLoiterAltQLand mode_lotier_qland; -#endif // This is the state of the flight control system // There are multiple states defined such as MANUAL, FBW-A, AUTO diff --git a/ArduPlane/control_modes.cpp b/ArduPlane/control_modes.cpp index 2ba1937da4..d97ce4212a 100644 --- a/ArduPlane/control_modes.cpp +++ b/ArduPlane/control_modes.cpp @@ -90,7 +90,7 @@ Mode *Plane::mode_from_mode_num(const enum Mode::Number num) break; #if HAL_QUADPLANE_ENABLED case Mode::Number::LOITER_ALT_QLAND: - ret = &mode_lotier_qland; + ret = &mode_loiter_qland; break; #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 54f618e9c8..e0a420a485 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -208,7 +208,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) #if HAL_QUADPLANE_ENABLED case Failsafe_Action_Loiter_alt_QLand: if (quadplane.available()) { - plane.set_mode(mode_lotier_qland, ModeReason::BATTERY_FAILSAFE); + plane.set_mode(mode_loiter_qland, ModeReason::BATTERY_FAILSAFE); break; } FALLTHROUGH; @@ -223,7 +223,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) case Failsafe_Action_Land: { bool already_landing = flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND; #if HAL_QUADPLANE_ENABLED - if (control_mode == &mode_qland || control_mode == &mode_lotier_qland) { + if (control_mode == &mode_qland || control_mode == &mode_loiter_qland) { already_landing = true; } #endif @@ -244,7 +244,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) case Failsafe_Action_RTL: { bool already_landing = flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND; #if HAL_QUADPLANE_ENABLED - if (control_mode == &mode_qland || control_mode == &mode_lotier_qland || + if (control_mode == &mode_qland || control_mode == &mode_loiter_qland || quadplane.in_vtol_land_sequence()) { already_landing = true; }