Plane: move braces to be around entire case in do_aux_function

This commit is contained in:
Peter Barker 2024-04-11 09:33:03 +10:00 committed by Peter Barker
parent 70b23733ac
commit 994e3edfb5
1 changed files with 8 additions and 6 deletions

View File

@ -95,9 +95,9 @@ void RC_Channel_Plane::do_aux_function_crow_mode(AuxSwitchPos ch_flag)
} }
} }
#if HAL_SOARING_ENABLED
void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag) void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag)
{ {
#if HAL_SOARING_ENABLED
SoaringController::ActiveStatus desired_state = SoaringController::ActiveStatus::SOARING_DISABLED; SoaringController::ActiveStatus desired_state = SoaringController::ActiveStatus::SOARING_DISABLED;
switch (ch_flag) { switch (ch_flag) {
@ -113,8 +113,8 @@ void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag)
} }
plane.g2.soaring_controller.set_pilot_desired_state(desired_state); plane.g2.soaring_controller.set_pilot_desired_state(desired_state);
#endif
} }
#endif
void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag) void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
{ {
@ -275,9 +275,11 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
} }
#endif #endif
#if HAL_SOARING_ENABLED
case AUX_FUNC::SOARING: case AUX_FUNC::SOARING:
do_aux_function_soaring_3pos(ch_flag); do_aux_function_soaring_3pos(ch_flag);
break; break;
#endif
case AUX_FUNC::FLAP: case AUX_FUNC::FLAP:
case AUX_FUNC::FBWA_TAILDRAGGER: case AUX_FUNC::FBWA_TAILDRAGGER:
@ -333,8 +335,8 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break; break;
#endif #endif
case AUX_FUNC::ARSPD_CALIBRATE:
#if AP_AIRSPEED_AUTOCAL_ENABLE #if AP_AIRSPEED_AUTOCAL_ENABLE
case AUX_FUNC::ARSPD_CALIBRATE:
switch (ch_flag) { switch (ch_flag) {
case AuxSwitchPos::HIGH: case AuxSwitchPos::HIGH:
plane.airspeed.set_calibration_enabled(true); plane.airspeed.set_calibration_enabled(true);
@ -345,20 +347,20 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
plane.airspeed.set_calibration_enabled(false); plane.airspeed.set_calibration_enabled(false);
break; break;
} }
#endif
break; break;
#endif
case AUX_FUNC::LANDING_FLARE: case AUX_FUNC::LANDING_FLARE:
do_aux_function_flare(ch_flag); do_aux_function_flare(ch_flag);
break; break;
case AUX_FUNC::PARACHUTE_RELEASE:
#if HAL_PARACHUTE_ENABLED #if HAL_PARACHUTE_ENABLED
case AUX_FUNC::PARACHUTE_RELEASE:
if (ch_flag == AuxSwitchPos::HIGH) { if (ch_flag == AuxSwitchPos::HIGH) {
plane.parachute_manual_release(); plane.parachute_manual_release();
} }
#endif
break; break;
#endif
case AUX_FUNC::MODE_SWITCH_RESET: case AUX_FUNC::MODE_SWITCH_RESET:
rc().reset_mode_switch(); rc().reset_mode_switch();