Copter: move #ifs to outside case statements in do_aux_function

this means a user will get a warning if they try to run a function and it isn't supported
This commit is contained in:
Peter Barker 2024-04-10 18:41:43 +10:00 committed by Peter Barker
parent d52f49ec36
commit cddc590b8b
1 changed files with 46 additions and 55 deletions

View File

@ -188,11 +188,11 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;
}
case AUX_FUNC::RTL:
#if MODE_RTL_ENABLED == ENABLED
case AUX_FUNC::RTL:
do_aux_function_change_mode(Mode::Number::RTL, ch_flag);
#endif
break;
#endif
case AUX_FUNC::SAVE_TRIM:
if ((ch_flag == AuxSwitchPos::HIGH) &&
@ -202,8 +202,8 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
}
break;
case AUX_FUNC::SAVE_WP:
#if MODE_AUTO_ENABLED == ENABLED
case AUX_FUNC::SAVE_WP:
// save waypoint when switch is brought high
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
@ -251,29 +251,27 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP);
}
}
#endif
break;
case AUX_FUNC::AUTO:
#if MODE_AUTO_ENABLED == ENABLED
do_aux_function_change_mode(Mode::Number::AUTO, ch_flag);
#endif
break;
#endif
#if RANGEFINDER_ENABLED == ENABLED
case AUX_FUNC::RANGEFINDER:
// enable or disable the rangefinder
#if RANGEFINDER_ENABLED == ENABLED
if ((ch_flag == AuxSwitchPos::HIGH) &&
copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
copter.rangefinder_state.enabled = true;
} else {
copter.rangefinder_state.enabled = false;
}
#endif
break;
#endif
case AUX_FUNC::ACRO_TRAINER:
#if MODE_ACRO_ENABLED == ENABLED
case AUX_FUNC::ACRO_TRAINER:
switch(ch_flag) {
case AuxSwitchPos::LOW:
copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::OFF);
@ -288,14 +286,14 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_LIMITED);
break;
}
#endif
break;
#endif
case AUX_FUNC::AUTOTUNE:
#if AUTOTUNE_ENABLED == ENABLED
case AUX_FUNC::AUTOTUNE:
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
#endif
break;
#endif
case AUX_FUNC::LAND:
do_aux_function_change_mode(Mode::Number::LAND, ch_flag);
@ -313,23 +311,19 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag);
break;
case AUX_FUNC::PARACHUTE_ENABLE:
#if PARACHUTE == ENABLED
case AUX_FUNC::PARACHUTE_ENABLE:
// Parachute enable/disable
copter.parachute.enabled(ch_flag == AuxSwitchPos::HIGH);
#endif
break;
case AUX_FUNC::PARACHUTE_RELEASE:
#if PARACHUTE == ENABLED
if (ch_flag == AuxSwitchPos::HIGH) {
copter.parachute_manual_release();
}
#endif
break;
case AUX_FUNC::PARACHUTE_3POS:
#if PARACHUTE == ENABLED
// Parachute disable, enable, release with 3 position switch
switch (ch_flag) {
case AuxSwitchPos::LOW:
@ -343,8 +337,8 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.parachute_manual_release();
break;
}
#endif
break;
#endif
case AUX_FUNC::ATTCON_FEEDFWD:
// enable or disable feed forward
@ -367,9 +361,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.ap.motor_interlock_switch = (ch_flag == AuxSwitchPos::HIGH || ch_flag == AuxSwitchPos::MIDDLE);
#endif
break;
#if FRAME_CONFIG == HELI_FRAME
case AUX_FUNC::TURBINE_START:
#if FRAME_CONFIG == HELI_FRAME
switch (ch_flag) {
case AuxSwitchPos::HIGH:
copter.motors->set_turb_start(true);
@ -381,23 +375,23 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.motors->set_turb_start(false);
break;
}
#endif
break;
case AUX_FUNC::BRAKE:
#endif
#if MODE_BRAKE_ENABLED == ENABLED
case AUX_FUNC::BRAKE:
do_aux_function_change_mode(Mode::Number::BRAKE, ch_flag);
#endif
break;
#endif
case AUX_FUNC::THROW:
#if MODE_THROW_ENABLED == ENABLED
case AUX_FUNC::THROW:
do_aux_function_change_mode(Mode::Number::THROW, ch_flag);
#endif
break;
#endif
case AUX_FUNC::PRECISION_LOITER:
#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED == ENABLED
case AUX_FUNC::PRECISION_LOITER:
switch (ch_flag) {
case AuxSwitchPos::HIGH:
copter.mode_loiter.set_precision_loiter_enabled(true);
@ -409,17 +403,17 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.mode_loiter.set_precision_loiter_enabled(false);
break;
}
#endif
break;
#endif
case AUX_FUNC::SMART_RTL:
#if MODE_SMARTRTL_ENABLED == ENABLED
case AUX_FUNC::SMART_RTL:
do_aux_function_change_mode(Mode::Number::SMART_RTL, ch_flag);
#endif
break;
#endif
case AUX_FUNC::INVERTED:
#if FRAME_CONFIG == HELI_FRAME
case AUX_FUNC::INVERTED:
switch (ch_flag) {
case AuxSwitchPos::HIGH:
if (copter.flightmode->allows_inverted()) {
@ -435,11 +429,11 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.attitude_control->set_inverted_flight(false);
break;
}
#endif
break;
#endif
case AUX_FUNC::WINCH_ENABLE:
#if AP_WINCH_ENABLED
case AUX_FUNC::WINCH_ENABLE:
switch (ch_flag) {
case AuxSwitchPos::HIGH:
// high switch position stops winch using rate control
@ -451,8 +445,8 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.g2.winch.relax();
break;
}
#endif
break;
#endif
case AUX_FUNC::WINCH_CONTROL:
// do nothing, used to control the rate of the winch and is processed within AP_Winch
@ -472,14 +466,12 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;
#endif
case AUX_FUNC::ZIGZAG:
#if MODE_ZIGZAG_ENABLED == ENABLED
case AUX_FUNC::ZIGZAG:
do_aux_function_change_mode(Mode::Number::ZIGZAG, ch_flag);
#endif
break;
case AUX_FUNC::ZIGZAG_SaveWP:
#if MODE_ZIGZAG_ENABLED == ENABLED
if (copter.flightmode == &copter.mode_zigzag) {
// initialize zigzag auto
copter.mode_zigzag.init_auto();
@ -495,47 +487,46 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;
}
}
#endif
break;
#endif
case AUX_FUNC::STABILIZE:
do_aux_function_change_mode(Mode::Number::STABILIZE, ch_flag);
break;
case AUX_FUNC::POSHOLD:
#if MODE_POSHOLD_ENABLED == ENABLED
case AUX_FUNC::POSHOLD:
do_aux_function_change_mode(Mode::Number::POSHOLD, ch_flag);
#endif
break;
#endif
case AUX_FUNC::ALTHOLD:
do_aux_function_change_mode(Mode::Number::ALT_HOLD, ch_flag);
break;
case AUX_FUNC::ACRO:
#if MODE_ACRO_ENABLED == ENABLED
case AUX_FUNC::ACRO:
do_aux_function_change_mode(Mode::Number::ACRO, ch_flag);
#endif
break;
#endif
case AUX_FUNC::FLOWHOLD:
#if MODE_FLOWHOLD_ENABLED
case AUX_FUNC::FLOWHOLD:
do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag);
#endif
break;
#endif
case AUX_FUNC::CIRCLE:
#if MODE_CIRCLE_ENABLED == ENABLED
case AUX_FUNC::CIRCLE:
do_aux_function_change_mode(Mode::Number::CIRCLE, ch_flag);
#endif
break;
#endif
case AUX_FUNC::DRIFT:
#if MODE_DRIFT_ENABLED == ENABLED
case AUX_FUNC::DRIFT:
do_aux_function_change_mode(Mode::Number::DRIFT, ch_flag);
#endif
break;
#endif
case AUX_FUNC::STANDBY: {
switch (ch_flag) {
@ -582,8 +573,8 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
}
break;
case AUX_FUNC::ZIGZAG_Auto:
#if MODE_ZIGZAG_ENABLED == ENABLED
case AUX_FUNC::ZIGZAG_Auto:
if (copter.flightmode == &copter.mode_zigzag) {
switch (ch_flag) {
case AuxSwitchPos::HIGH:
@ -594,8 +585,8 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;
}
}
#endif
break;
#endif
case AUX_FUNC::AIRMODE:
do_aux_function_change_air_mode(ch_flag);
@ -608,17 +599,17 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
do_aux_function_change_force_flying(ch_flag);
break;
case AUX_FUNC::AUTO_RTL:
#if MODE_AUTO_ENABLED == ENABLED
case AUX_FUNC::AUTO_RTL:
do_aux_function_change_mode(Mode::Number::AUTO_RTL, ch_flag);
#endif
break;
#endif
case AUX_FUNC::TURTLE:
#if MODE_TURTLE_ENABLED == ENABLED
case AUX_FUNC::TURTLE:
do_aux_function_change_mode(Mode::Number::TURTLE, ch_flag);
#endif
break;
#endif
case AUX_FUNC::SIMPLE_HEADING_RESET:
if (ch_flag == AuxSwitchPos::HIGH) {