diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index fd1ef73d9c811..fdb175f80c5b8 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 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: diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index bbb8d234486ea..2fb494f1a6b5e 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1362,9 +1362,15 @@ struct RCConversionInfo { static const RCConversionInfo rc_option_conversion[] = { { Parameters::k_param_flapin_channel_old, 0, RC_Channel::AUX_FUNC::FLAP}, { Parameters::k_param_g2, 968, RC_Channel::AUX_FUNC::SOARING}, +#if AP_FENCE_ENABLED { Parameters::k_param_fence_channel, 0, RC_Channel::AUX_FUNC::FENCE}, +#endif +#if AP_MISSION_ENABLED { Parameters::k_param_reset_mission_chan, 0, RC_Channel::AUX_FUNC::MISSION_RESET}, +#endif +#if HAL_PARACHUTE_ENABLED { Parameters::k_param_parachute_channel, 0, RC_Channel::AUX_FUNC::PARACHUTE_RELEASE}, +#endif { Parameters::k_param_fbwa_tdrag_chan, 0, RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER}, { Parameters::k_param_reset_switch_chan, 0, RC_Channel::AUX_FUNC::MODE_SWITCH_RESET}, }; diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index d674c55806f07..ac05d1174af0a 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -157,7 +157,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option, case AUX_FUNC::FBWA_TAILDRAGGER: case AUX_FUNC::FWD_THR: case AUX_FUNC::LANDING_FLARE: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif case AUX_FUNC::MODE_SWITCH_RESET: case AUX_FUNC::CRUISE: #if HAL_QUADPLANE_ENABLED diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index 25ff58622a9da..12f5b8c3946c9 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -190,6 +190,9 @@ def test_disable_feature(self, feature, options): self.test_compile_with_defines(defines) + self.assert_feature_not_in_code(defines, feature) + + def assert_feature_not_in_code(self, defines, feature): # if the feature is truly disabled then extract_features.py # should say so: for target in self.build_targets: @@ -222,6 +225,177 @@ def test_enable_feature(self, feature, options): self.test_compile_with_defines(defines) + self.assert_feature_in_code(defines, feature) + + def define_is_whitelisted_for_feature_in_code(self, target, define): + '''returns true if we can not expect the define to be extracted from + the binary''' + # the following defines are known not to work on some + # or all vehicles: + feature_define_whitelist = set([ + 'AP_RANGEFINDER_ENABLED', # only at vehicle level ATM + 'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # no symbol + 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', # broken, no subscriber + # Baro drivers either come in because you have + # external-probing enabled or you have them specified in + # your hwdef. If you're not probing and its not in your + # hwdef then the code will be elided as unreachable + 'AP_BARO_ICM20789_ENABLED', + 'AP_BARO_ICP101XX_ENABLED', + 'AP_BARO_ICP201XX_ENABLED', + 'AP_BARO_BMP085_ENABLED', + 'AP_BARO_BMP280_ENABLED', + 'AP_BARO_BMP388_ENABLED', + 'AP_BARO_BMP581_ENABLED', + 'AP_BARO_DPS280_ENABLED', + 'AP_BARO_FBM320_ENABLED', + 'AP_BARO_KELLERLD_ENABLED', + 'AP_BARO_LPS2XH_ENABLED', + 'AP_BARO_MS56XX_ENABLED', + 'AP_BARO_SPL06_ENABLED', + 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', # elided unless AP_CAMERA_SEND_FOV_STATUS_ENABLED + 'AP_COMPASS_LSM9DS1_ENABLED', # must be in hwdef, not probed + 'AP_COMPASS_MAG3110_ENABLED', # must be in hwdef, not probed + 'AP_COMPASS_MMC5XX3_ENABLED', # must be in hwdef, not probed + 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', # completely elided + 'AP_MAVLINK_MSG_HIL_GPS_ENABLED', # no symbol available + 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', # no symbol available + 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', # no symbol available + 'HAL_MSP_SENSORS_ENABLED', # no symbol available + 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', # FIXME: need a new define/feature + 'HAL_OSD_SIDEBAR_ENABLE', # FIXME: need a new define/feature + 'HAL_PLUSCODE_ENABLE', # FIXME: need a new define/feature + 'AP_SERIALMANAGER_REGISTER_ENABLED', # completely elided without a caller + 'AP_OPTICALFLOW_ONBOARD_ENABLED', # only instantiated on Linux + 'HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', # entirely elided if no user + 'AP_PLANE_BLACKBOX_LOGGING', # entirely elided if no user + ]) + if target.lower() != "copter": + feature_define_whitelist.add('MODE_ZIGZAG_ENABLED') + feature_define_whitelist.add('MODE_SYSTEMID_ENABLED') + feature_define_whitelist.add('MODE_SPORT_ENABLED') + feature_define_whitelist.add('MODE_FOLLOW_ENABLED') + feature_define_whitelist.add('MODE_TURTLE_ENABLED') + feature_define_whitelist.add('MODE_GUIDED_NOGPS_ENABLED') + feature_define_whitelist.add('MODE_FLOWHOLD_ENABLED') + feature_define_whitelist.add('MODE_FLIP_ENABLED') + feature_define_whitelist.add('MODE_BRAKE_ENABLED') + feature_define_whitelist.add('AP_TEMPCALIBRATION_ENABLED') + feature_define_whitelist.add('AC_PAYLOAD_PLACE_ENABLED') + feature_define_whitelist.add('AP_AVOIDANCE_ENABLED') + feature_define_whitelist.add('AP_WINCH_ENABLED') + feature_define_whitelist.add('AP_WINCH_DAIWA_ENABLED') + feature_define_whitelist.add('AP_WINCH_PWM_ENABLED') + feature_define_whitelist.add(r'AP_MOTORS_FRAME_.*_ENABLED') + + if target.lower() != "plane": + # only on Plane: + feature_define_whitelist.add('AP_ICENGINE_ENABLED') + feature_define_whitelist.add('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED') + feature_define_whitelist.add('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED') + feature_define_whitelist.add('AP_ADVANCEDFAILSAFE_ENABLED') + feature_define_whitelist.add('AP_TUNING_ENABLED') + feature_define_whitelist.add('HAL_LANDING_DEEPSTALL_ENABLED') + feature_define_whitelist.add('HAL_SOARING_ENABLED') + feature_define_whitelist.add('AP_PLANE_BLACKBOX_LOGGING') + feature_define_whitelist.add('QAUTOTUNE_ENABLED') + feature_define_whitelist.add('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED') + feature_define_whitelist.add('HAL_QUADPLANE_ENABLED') + feature_define_whitelist.add('AP_BATTERY_WATT_MAX_ENABLED') + + if target.lower() not in ["plane", "copter"]: + feature_define_whitelist.add('HAL_ADSB_ENABLED') + feature_define_whitelist.add('AP_LANDINGGEAR_ENABLED') + # only Plane and Copter instantiate Parachute + feature_define_whitelist.add('HAL_PARACHUTE_ENABLED') + # only Plane and Copter have AP_Motors: + + if target.lower() not in ["rover", "copter"]: + # only Plane and Copter instantiate Beacon + feature_define_whitelist.add('AP_BEACON_ENABLED') + + if target.lower() != "rover": + # only on Rover: + feature_define_whitelist.add('HAL_TORQEEDO_ENABLED') + feature_define_whitelist.add('AP_ROVER_ADVANCED_FAILSAFE_ENABLED') + if target.lower() != "sub": + # only on Sub: + feature_define_whitelist.add('AP_BARO_KELLERLD_ENABLED') + if target.lower() not in frozenset(["rover", "sub"]): + # only Rover and Sub get nmea airspeed + feature_define_whitelist.add('AP_AIRSPEED_NMEA_ENABLED') + if target.lower() not in frozenset(["copter", "rover"]): + feature_define_whitelist.add('HAL_SPRAYER_ENABLED') + feature_define_whitelist.add('HAL_PROXIMITY_ENABLED') + feature_define_whitelist.add('AP_PROXIMITY_.*_ENABLED') + feature_define_whitelist.add('AP_OAPATHPLANNER_ENABLED') + + if target.lower() in ["blimp", "antennatracker"]: + # no airspeed on blimp/tracker + feature_define_whitelist.add(r'AP_AIRSPEED_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MOUNT_ENABLED') + feature_define_whitelist.add(r'AP_MOUNT_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MOUNT_.*_ENABLED') + feature_define_whitelist.add(r'HAL_SOLO_GIMBAL_ENABLED') + feature_define_whitelist.add(r'AP_OPTICALFLOW_ENABLED') + feature_define_whitelist.add(r'AP_OPTICALFLOW_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MSP_OPTICALFLOW_ENABLED') + # missing calls to fence.check(): + feature_define_whitelist.add(r'AP_FENCE_ENABLED') + # RPM not instantiated on Blimp or Rover: + feature_define_whitelist.add(r'AP_RPM_ENABLED') + feature_define_whitelist.add(r'AP_RPM_.*_ENABLED') + # rangefinder init is not called: + feature_define_whitelist.add(r'HAL_MSP_RANGEFINDER_ENABLED') + # these guys don't instantiate anything which uses sd-card storage: + feature_define_whitelist.add(r'AP_SDCARD_STORAGE_ENABLED') + feature_define_whitelist.add(r'AP_RANGEFINDER_ENABLED') + feature_define_whitelist.add(r'AP_RANGEFINDER_.*_ENABLED') + + if target.lower() in ["blimp", "antennatracker", "sub"]: + # no OSD on Sub/blimp/tracker + feature_define_whitelist.add(r'OSD_ENABLED') + feature_define_whitelist.add(r'OSD_PARAM_ENABLED') + # AP_OSD is not instantiated, , so no MSP backend: + feature_define_whitelist.add(r'HAL_WITH_MSP_DISPLAYPORT') + # camera instantiated in specific vehicles: + feature_define_whitelist.add(r'AP_CAMERA_ENABLED') + feature_define_whitelist.add(r'AP_CAMERA_.*_ENABLED') + # button update is not called in these vehicles + feature_define_whitelist.add(r'HAL_BUTTON_ENABLED') + # precland not instantiated on these vehicles + feature_define_whitelist.add(r'AC_PRECLAND_ENABLED') + feature_define_whitelist.add(r'AC_PRECLAND_.*_ENABLED') + # RSSI is not initialised - probably should be for some + feature_define_whitelist.add(r'AP_RSSI_ENABLED') + + if target.lower() in ["antennatracker", "sub"]: + # missing the init call to the relay library: + feature_define_whitelist.add(r'AP_RELAY_ENABLED') + feature_define_whitelist.add(r'AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED') + + for some_re in feature_define_whitelist: + if re.match(some_re, define): + return True + + def assert_feature_in_code(self, defines, feature): + # if the feature is truly disabled then extract_features.py + # should say so: + for target in self.build_targets: + path = self.target_to_elf_path(target) + extracter = extract_features.ExtractFeatures(path) + (compiled_in_feature_defines, not_compiled_in_feature_defines) = extracter.extract() + for define in defines: + if not defines[define]: + continue + if define in compiled_in_feature_defines: + continue + error = f"feature gated by {define} not compiled into ({target}); extract_features.py bug?" + if self.define_is_whitelisted_for_feature_in_code(target, define): + print("warn: " + error) + continue + raise ValueError(error) + def board(self): '''returns board to build for''' return self._board diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index b37f20051a97a..8c88c2be26a3b 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -2,6 +2,10 @@ /// @brief Parachute release library #pragma once +#include "AP_Parachute_config.h" + +#if HAL_PARACHUTE_ENABLED + #include #include @@ -22,13 +26,6 @@ #define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute #define AP_PARACHUTE_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release -#ifndef HAL_PARACHUTE_ENABLED -// default to parachute enabled to match previous configs -#define HAL_PARACHUTE_ENABLED 1 -#endif - -#if HAL_PARACHUTE_ENABLED - /// @class AP_Parachute /// @brief Class managing the release of a parachute class AP_Parachute { diff --git a/libraries/AP_Parachute/AP_Parachute_config.h b/libraries/AP_Parachute/AP_Parachute_config.h new file mode 100644 index 0000000000000..0d646cdb7a473 --- /dev/null +++ b/libraries/AP_Parachute/AP_Parachute_config.h @@ -0,0 +1,8 @@ +#pragma once + +#include + +#ifndef HAL_PARACHUTE_ENABLED +// default to parachute enabled to match previous configs +#define HAL_PARACHUTE_ENABLED 1 +#endif diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 5c424706cb9dc..da239932b386a 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -59,6 +59,7 @@ extern const AP_HAL::HAL& hal; #include #include #include +#include #define SWITCH_DEBOUNCE_TIME_MS 200 const AP_Param::GroupInfo RC_Channel::var_info[] = { @@ -628,17 +629,23 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos // init channel options switch (ch_option) { // the following functions do not need to be initialised: +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM_AIRMODE: +#endif #if AP_BATTERY_ENABLED case AUX_FUNC::BATTERY_MPPT_ENABLE: #endif #if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_TRIGGER: #endif +#if AP_MISSION_ENABLED case AUX_FUNC::CLEAR_WP: +#endif case AUX_FUNC::COMPASS_LEARN: +#if AP_ARMING_ENABLED case AUX_FUNC::DISARM: +#endif case AUX_FUNC::DO_NOTHING: #if AP_LANDINGGEAR_ENABLED case AUX_FUNC::LANDING_GEAR: @@ -655,12 +662,16 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos #if HAL_VISUALODOM_ENABLED case AUX_FUNC::VISODOM_ALIGN: #endif +#if AP_AHRS_ENABLED case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_YAW_RESET: +#endif #if HAL_GENERATOR_ENABLED case AUX_FUNC::GENERATOR: // don't turn generator on or off initially #endif +#if AP_AHRS_ENABLED case AUX_FUNC::EKF_POS_SOURCE: +#endif #if HAL_TORQEEDO_ENABLED case AUX_FUNC::TORQEEDO_CLEAR_ERR: #endif @@ -689,19 +700,23 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::MOUNT2_PITCH: case AUX_FUNC::MOUNT2_YAW: #endif +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_STARTER: +#endif +#if COMPASS_CAL_ENABLED case AUX_FUNC::MAG_CAL: +#endif #if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_IMAGE_TRACKING: #endif #if HAL_MOUNT_ENABLED case AUX_FUNC::MOUNT_LRF_ENABLE: #endif - break; - - // not really aux functions: +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_THROTTLE: +#endif break; + #if HAL_ADSB_ENABLED case AUX_FUNC::AVOID_ADSB: #endif @@ -721,7 +736,9 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::KILL_IMU2: case AUX_FUNC::KILL_IMU3: #endif +#if AP_MISSION_ENABLED case AUX_FUNC::MISSION_RESET: +#endif case AUX_FUNC::MOTOR_ESTOP: case AUX_FUNC::RC_OVERRIDE_ENABLE: #if HAL_RUNCAM_ENABLED @@ -731,7 +748,9 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos #if HAL_SPRAYER_ENABLED case AUX_FUNC::SPRAYER: #endif +#if AP_AIRSPEED_ENABLED case AUX_FUNC::DISABLE_AIRSPEED_USE: +#endif case AUX_FUNC::FFT_NOTCH_TUNE: #if HAL_MOUNT_ENABLED case AUX_FUNC::RETRACT_MOUNT1: @@ -749,9 +768,11 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::CAMERA_AUTO_FOCUS: case AUX_FUNC::CAMERA_LENS: #endif +#if AP_AHRS_ENABLED case AUX_FUNC::AHRS_TYPE: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; +#endif default: GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n", (unsigned)(this->ch_in+1), (unsigned)ch_option); @@ -766,61 +787,111 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const RC_Channel::LookupTable RC_Channel::lookuptable[] = { +#if AP_MISSION_ENABLED { AUX_FUNC::SAVE_WP,"SaveWaypoint"}, +#endif +#if AP_CAMERA_ENABLED { AUX_FUNC::CAMERA_TRIGGER,"CameraTrigger"}, +#endif +#if AP_RANGEFINDER_ENABLED { AUX_FUNC::RANGEFINDER,"Rangefinder"}, +#endif +#if AP_FENCE_ENABLED { AUX_FUNC::FENCE,"Fence"}, +#endif +#if HAL_SPRAYER_ENABLED { AUX_FUNC::SPRAYER,"Sprayer"}, +#endif +#if HAL_PARACHUTE_ENABLED { AUX_FUNC::PARACHUTE_ENABLE,"ParachuteEnable"}, { AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"}, { AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"}, +#endif +#if AP_MISSION_ENABLED { AUX_FUNC::MISSION_RESET,"MissionReset"}, +#endif #if HAL_MOUNT_ENABLED { AUX_FUNC::RETRACT_MOUNT1,"RetractMount1"}, { AUX_FUNC::RETRACT_MOUNT2,"RetractMount2"}, #endif +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY,"Relay1"}, +#endif { AUX_FUNC::MOTOR_ESTOP,"MotorEStop"}, { AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"}, +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY2,"Relay2"}, { AUX_FUNC::RELAY3,"Relay3"}, { AUX_FUNC::RELAY4,"Relay4"}, +#endif { AUX_FUNC::PRECISION_LOITER,"PrecisionLoiter"}, { AUX_FUNC::AVOID_PROXIMITY,"AvoidProximity"}, +#if AP_WINCH_ENABLED { AUX_FUNC::WINCH_ENABLE,"WinchEnable"}, { AUX_FUNC::WINCH_CONTROL,"WinchControl"}, +#endif +#if AP_MISSION_ENABLED { AUX_FUNC::CLEAR_WP,"ClearWaypoint"}, +#endif { AUX_FUNC::COMPASS_LEARN,"CompassLearn"}, { AUX_FUNC::SAILBOAT_TACK,"SailboatTack"}, +#if AP_GPS_ENABLED { AUX_FUNC::GPS_DISABLE,"GPSDisable"}, { AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"}, +#endif +#if AP_AIRSPEED_ENABLED { AUX_FUNC::DISABLE_AIRSPEED_USE,"DisableAirspeedUse"}, +#endif +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY5,"Relay5"}, { AUX_FUNC::RELAY6,"Relay6"}, +#endif { AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"}, { AUX_FUNC::SURFACE_TRACKING,"SurfaceTracking"}, +#if HAL_RUNCAM_ENABLED { AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"}, { AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"}, +#endif +#if HAL_VISUALODOM_ENABLED { AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"}, +#endif { AUX_FUNC::AIRMODE, "AirMode"}, +#if AP_CAMERA_ENABLED { AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"}, +#endif +#if HAL_GENERATOR_ENABLED { AUX_FUNC::GENERATOR,"Generator"}, +#endif +#if AP_BATTERY_ENABLED { AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"}, +#endif +#if AP_AIRSPEED_AUTOCAL_ENABLE { AUX_FUNC::ARSPD_CALIBRATE,"Calibrate Airspeed"}, +#endif +#if HAL_TORQEEDO_ENABLED { AUX_FUNC::TORQEEDO_CLEAR_ERR, "Torqeedo Clear Err"}, +#endif { AUX_FUNC::EMERGENCY_LANDING_EN, "Emergency Landing"}, { AUX_FUNC::WEATHER_VANE_ENABLE, "Weathervane"}, { AUX_FUNC::TURBINE_START, "Turbine Start"}, { AUX_FUNC::FFT_NOTCH_TUNE, "FFT Notch Tuning"}, +#if HAL_MOUNT_ENABLED { AUX_FUNC::MOUNT_LOCK, "MountLock"}, +#endif +#if HAL_LOGGING_ENABLED { AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"}, +#endif +#if AP_CAMERA_ENABLED { AUX_FUNC::CAMERA_REC_VIDEO, "Camera Record Video"}, { AUX_FUNC::CAMERA_ZOOM, "Camera Zoom"}, { AUX_FUNC::CAMERA_MANUAL_FOCUS, "Camera Manual Focus"}, { AUX_FUNC::CAMERA_AUTO_FOCUS, "Camera Auto Focus"}, { AUX_FUNC::CAMERA_IMAGE_TRACKING, "Camera Image Tracking"}, { AUX_FUNC::CAMERA_LENS, "Camera Lens"}, +#endif +#if HAL_MOUNT_ENABLED { AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"}, +#endif }; /* lookup the announcement for switch change */ @@ -910,10 +981,14 @@ bool RC_Channel::read_aux() bool RC_Channel::init_position_on_first_radio_read(AUX_FUNC func) const { switch (func) { +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARM_EMERGENCY_STOP: +#endif +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif // we do not want to process return true; @@ -1408,12 +1483,14 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; #endif +#if AP_MISSION_ENABLED case AUX_FUNC::CLEAR_WP: do_aux_function_clear_wp(ch_flag); break; case AUX_FUNC::MISSION_RESET: do_aux_function_mission_reset(ch_flag); break; +#endif #if HAL_ADSB_ENABLED case AUX_FUNC::AVOID_ADSB: @@ -1449,6 +1526,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch do_aux_function_lost_vehicle_sound(ch_flag); break; +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM: do_aux_function_armdisarm(ch_flag); break; @@ -1458,6 +1536,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch AP::arming().disarm(AP_Arming::Method::AUXSWITCH); } break; +#endif case AUX_FUNC::COMPASS_LEARN: if (ch_flag == AuxSwitchPos::HIGH) { @@ -1734,6 +1813,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; } +#if AP_AHRS_ENABLED case AUX_FUNC::EKF_LANE_SWITCH: // used to test emergency lane switch AP::ahrs().check_lane_switch(); @@ -1750,7 +1830,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch #endif break; } - +#endif // AP_AHRS_ENABLED #if HAL_TORQEEDO_ENABLED // clear torqeedo error @@ -1766,12 +1846,15 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch #endif // do nothing for these functions +#if HAL_MOUNT_ENABLED case AUX_FUNC::MOUNT1_ROLL: case AUX_FUNC::MOUNT1_PITCH: case AUX_FUNC::MOUNT1_YAW: case AUX_FUNC::MOUNT2_ROLL: case AUX_FUNC::MOUNT2_PITCH: case AUX_FUNC::MOUNT2_YAW: +#endif +#if AP_SCRIPTING_ENABLED case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_3: @@ -1780,12 +1863,15 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::SCRIPTING_6: case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_8: +#endif break; +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_THROTTLE: case AUX_FUNC::LOWEHEISER_STARTER: // monitored by the library itself break; +#endif default: GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);