5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-08 17:08:28 -04:00

Plane: correct spelling of mode_lotier_qland

This commit is contained in:
Peter Barker 2022-02-04 14:24:05 +11:00 committed by Andrew Tridgell
parent 7c0b1f46d6
commit 4068d57930
3 changed files with 5 additions and 7 deletions

View File

@ -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

View File

@ -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

View File

@ -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;
}