From c98e0212b16cc7b1e73c139f031993916ad43b8c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Mar 2024 21:04:28 +1100 Subject: [PATCH] ArduCopter: remove AUX_FUNC entries based on feature defines --- ArduCopter/RC_Channel.cpp | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 0ae33562a80df7..29e502f2877e82 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -87,7 +87,9 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::GUIDED: case AUX_FUNC::LAND: case AUX_FUNC::LOITER: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif case AUX_FUNC::POSHOLD: case AUX_FUNC::RESETTOARMEDYAW: case AUX_FUNC::RTL: @@ -99,7 +101,9 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::USER_FUNC1: case AUX_FUNC::USER_FUNC2: case AUX_FUNC::USER_FUNC3: +#if AP_WINCH_ENABLED case AUX_FUNC::WINCH_CONTROL: +#endif case AUX_FUNC::ZIGZAG: case AUX_FUNC::ZIGZAG_Auto: case AUX_FUNC::ZIGZAG_SaveWP: @@ -116,15 +120,21 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::ATTCON_FEEDFWD: case AUX_FUNC::INVERTED: case AUX_FUNC::MOTOR_INTERLOCK: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release case AUX_FUNC::PARACHUTE_ENABLE: +#endif case AUX_FUNC::PRECISION_LOITER: +#if AP_RANGEFINDER_ENABLED case AUX_FUNC::RANGEFINDER: +#endif case AUX_FUNC::SIMPLE_MODE: case AUX_FUNC::STANDBY: case AUX_FUNC::SUPERSIMPLE_MODE: case AUX_FUNC::SURFACE_TRACKING: +#if AP_WINCH_ENABLED case AUX_FUNC::WINCH_ENABLE: +#endif case AUX_FUNC::AIRMODE: case AUX_FUNC::FORCEFLYING: case AUX_FUNC::CUSTOM_CONTROLLER: @@ -270,7 +280,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc copter.rangefinder_state.enabled = false; } break; -#endif +#endif // AP_RANGEFINDER_ENABLED #if MODE_ACRO_ENABLED == ENABLED case AUX_FUNC::ACRO_TRAINER: @@ -343,7 +353,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } break; -#endif +#endif // HAL_PARACHUTE_ENABLED case AUX_FUNC::ATTCON_FEEDFWD: // enable or disable feed forward @@ -451,11 +461,11 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } break; -#endif case AUX_FUNC::WINCH_CONTROL: // do nothing, used to control the rate of the winch and is processed within AP_Winch break; +#endif // AP_WINCH_ENABLED #ifdef USERHOOK_AUXSWITCH case AUX_FUNC::USER_FUNC1: