RC_Channel: produce error if feature compiled out and aux func initialised

This commit is contained in:
Peter Barker 2024-07-04 15:40:08 +10:00 committed by Peter Barker
parent ce48932f4d
commit 6ce7e179d7

View File

@ -626,26 +626,41 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
// the following functions do not need to be initialised: // the following functions do not need to be initialised:
case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM:
case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM_AIRMODE:
#if AP_BATTERY_ENABLED
case AUX_FUNC::BATTERY_MPPT_ENABLE: case AUX_FUNC::BATTERY_MPPT_ENABLE:
#endif
#if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_TRIGGER: case AUX_FUNC::CAMERA_TRIGGER:
#endif
case AUX_FUNC::CLEAR_WP: case AUX_FUNC::CLEAR_WP:
case AUX_FUNC::COMPASS_LEARN: case AUX_FUNC::COMPASS_LEARN:
case AUX_FUNC::DISARM: case AUX_FUNC::DISARM:
case AUX_FUNC::DO_NOTHING: case AUX_FUNC::DO_NOTHING:
#if AP_LANDINGGEAR_ENABLED
case AUX_FUNC::LANDING_GEAR: case AUX_FUNC::LANDING_GEAR:
#endif
case AUX_FUNC::LOST_VEHICLE_SOUND: case AUX_FUNC::LOST_VEHICLE_SOUND:
#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED
case AUX_FUNC::RELAY: case AUX_FUNC::RELAY:
case AUX_FUNC::RELAY2: case AUX_FUNC::RELAY2:
case AUX_FUNC::RELAY3: case AUX_FUNC::RELAY3:
case AUX_FUNC::RELAY4: case AUX_FUNC::RELAY4:
case AUX_FUNC::RELAY5: case AUX_FUNC::RELAY5:
case AUX_FUNC::RELAY6: case AUX_FUNC::RELAY6:
#endif
#if HAL_VISUALODOM_ENABLED
case AUX_FUNC::VISODOM_ALIGN: case AUX_FUNC::VISODOM_ALIGN:
#endif
case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_LANE_SWITCH:
case AUX_FUNC::EKF_YAW_RESET: case AUX_FUNC::EKF_YAW_RESET:
#if HAL_GENERATOR_ENABLED
case AUX_FUNC::GENERATOR: // don't turn generator on or off initially case AUX_FUNC::GENERATOR: // don't turn generator on or off initially
#endif
case AUX_FUNC::EKF_POS_SOURCE: case AUX_FUNC::EKF_POS_SOURCE:
#if HAL_TORQEEDO_ENABLED
case AUX_FUNC::TORQEEDO_CLEAR_ERR: case AUX_FUNC::TORQEEDO_CLEAR_ERR:
#endif
#if AP_SCRIPTING_ENABLED
case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_1:
case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_2:
case AUX_FUNC::SCRIPTING_3: case AUX_FUNC::SCRIPTING_3:
@ -654,21 +669,30 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
case AUX_FUNC::SCRIPTING_6: case AUX_FUNC::SCRIPTING_6:
case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_7:
case AUX_FUNC::SCRIPTING_8: case AUX_FUNC::SCRIPTING_8:
#endif
#if AP_VIDEOTX_ENABLED #if AP_VIDEOTX_ENABLED
case AUX_FUNC::VTX_POWER: case AUX_FUNC::VTX_POWER:
#endif #endif
#if AP_OPTICALFLOW_CALIBRATOR_ENABLED
case AUX_FUNC::OPTFLOW_CAL: case AUX_FUNC::OPTFLOW_CAL:
#endif
case AUX_FUNC::TURBINE_START: case AUX_FUNC::TURBINE_START:
#if HAL_MOUNT_ENABLED
case AUX_FUNC::MOUNT1_ROLL: case AUX_FUNC::MOUNT1_ROLL:
case AUX_FUNC::MOUNT1_PITCH: case AUX_FUNC::MOUNT1_PITCH:
case AUX_FUNC::MOUNT1_YAW: case AUX_FUNC::MOUNT1_YAW:
case AUX_FUNC::MOUNT2_ROLL: case AUX_FUNC::MOUNT2_ROLL:
case AUX_FUNC::MOUNT2_PITCH: case AUX_FUNC::MOUNT2_PITCH:
case AUX_FUNC::MOUNT2_YAW: case AUX_FUNC::MOUNT2_YAW:
#endif
case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::LOWEHEISER_STARTER:
case AUX_FUNC::MAG_CAL: case AUX_FUNC::MAG_CAL:
#if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_IMAGE_TRACKING: case AUX_FUNC::CAMERA_IMAGE_TRACKING:
#endif
#if HAL_MOUNT_ENABLED
case AUX_FUNC::MOUNT_LRF_ENABLE: case AUX_FUNC::MOUNT_LRF_ENABLE:
#endif
break; break;
// not really aux functions: // not really aux functions:
@ -678,9 +702,13 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
case AUX_FUNC::AVOID_ADSB: case AUX_FUNC::AVOID_ADSB:
#endif #endif
case AUX_FUNC::AVOID_PROXIMITY: case AUX_FUNC::AVOID_PROXIMITY:
#if AP_FENCE_ENABLED
case AUX_FUNC::FENCE: case AUX_FUNC::FENCE:
#endif
#if AP_GPS_ENABLED
case AUX_FUNC::GPS_DISABLE: case AUX_FUNC::GPS_DISABLE:
case AUX_FUNC::GPS_DISABLE_YAW: case AUX_FUNC::GPS_DISABLE_YAW:
#endif
#if AP_GRIPPER_ENABLED #if AP_GRIPPER_ENABLED
case AUX_FUNC::GRIPPER: case AUX_FUNC::GRIPPER:
#endif #endif
@ -692,22 +720,30 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
case AUX_FUNC::MISSION_RESET: case AUX_FUNC::MISSION_RESET:
case AUX_FUNC::MOTOR_ESTOP: case AUX_FUNC::MOTOR_ESTOP:
case AUX_FUNC::RC_OVERRIDE_ENABLE: case AUX_FUNC::RC_OVERRIDE_ENABLE:
#if HAL_RUNCAM_ENABLED
case AUX_FUNC::RUNCAM_CONTROL: case AUX_FUNC::RUNCAM_CONTROL:
case AUX_FUNC::RUNCAM_OSD_CONTROL: case AUX_FUNC::RUNCAM_OSD_CONTROL:
#endif
#if HAL_SPRAYER_ENABLED
case AUX_FUNC::SPRAYER: case AUX_FUNC::SPRAYER:
#endif
case AUX_FUNC::DISABLE_AIRSPEED_USE: case AUX_FUNC::DISABLE_AIRSPEED_USE:
case AUX_FUNC::FFT_NOTCH_TUNE: case AUX_FUNC::FFT_NOTCH_TUNE:
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
case AUX_FUNC::RETRACT_MOUNT1: case AUX_FUNC::RETRACT_MOUNT1:
case AUX_FUNC::MOUNT_LOCK: case AUX_FUNC::MOUNT_LOCK:
#endif #endif
#if HAL_LOGGING_ENABLED
case AUX_FUNC::LOG_PAUSE: case AUX_FUNC::LOG_PAUSE:
#endif
case AUX_FUNC::ARM_EMERGENCY_STOP: case AUX_FUNC::ARM_EMERGENCY_STOP:
#if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_REC_VIDEO: case AUX_FUNC::CAMERA_REC_VIDEO:
case AUX_FUNC::CAMERA_ZOOM: case AUX_FUNC::CAMERA_ZOOM:
case AUX_FUNC::CAMERA_MANUAL_FOCUS: case AUX_FUNC::CAMERA_MANUAL_FOCUS:
case AUX_FUNC::CAMERA_AUTO_FOCUS: case AUX_FUNC::CAMERA_AUTO_FOCUS:
case AUX_FUNC::CAMERA_LENS: case AUX_FUNC::CAMERA_LENS:
#endif
case AUX_FUNC::AHRS_TYPE: case AUX_FUNC::AHRS_TYPE:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
break; break;
@ -1049,9 +1085,9 @@ bool RC_Channel::do_aux_function_camera_lens(const AuxSwitchPos ch_flag)
} }
#endif // AP_CAMERA_ENABLED #endif // AP_CAMERA_ENABLED
#if HAL_RUNCAM_ENABLED
void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag)
{ {
#if HAL_RUNCAM_ENABLED
AP_RunCam *runcam = AP::runcam(); AP_RunCam *runcam = AP::runcam();
if (runcam == nullptr) { if (runcam == nullptr) {
return; return;
@ -1068,12 +1104,10 @@ void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag)
runcam->stop_recording(); runcam->stop_recording();
break; break;
} }
#endif
} }
void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag)
{ {
#if HAL_RUNCAM_ENABLED
AP_RunCam *runcam = AP::runcam(); AP_RunCam *runcam = AP::runcam();
if (runcam == nullptr) { if (runcam == nullptr) {
return; return;
@ -1088,8 +1122,8 @@ void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag)
runcam->exit_osd(); runcam->exit_osd();
break; break;
} }
#endif
} }
#endif
#if AP_FENCE_ENABLED #if AP_FENCE_ENABLED
// enable or disable the fence // enable or disable the fence
@ -1328,6 +1362,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
break; break;
#endif // AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED #endif // AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED
#if HAL_RUNCAM_ENABLED
case AUX_FUNC::RUNCAM_CONTROL: case AUX_FUNC::RUNCAM_CONTROL:
do_aux_function_runcam_control(ch_flag); do_aux_function_runcam_control(ch_flag);
break; break;
@ -1335,6 +1370,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
case AUX_FUNC::RUNCAM_OSD_CONTROL: case AUX_FUNC::RUNCAM_OSD_CONTROL:
do_aux_function_runcam_osd_control(ch_flag); do_aux_function_runcam_osd_control(ch_flag);
break; break;
#endif
case AUX_FUNC::CLEAR_WP: case AUX_FUNC::CLEAR_WP:
do_aux_function_clear_wp(ch_flag); do_aux_function_clear_wp(ch_flag);
@ -1415,6 +1451,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
} }
#endif #endif
#if AP_GPS_ENABLED
case AUX_FUNC::GPS_DISABLE: case AUX_FUNC::GPS_DISABLE:
AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH); AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH);
#if HAL_EXTERNAL_AHRS_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED
@ -1425,6 +1462,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
case AUX_FUNC::GPS_DISABLE_YAW: case AUX_FUNC::GPS_DISABLE_YAW:
AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH); AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH);
break; break;
#endif // AP_GPS_ENABLED
#if AP_AIRSPEED_ENABLED #if AP_AIRSPEED_ENABLED
case AUX_FUNC::DISABLE_AIRSPEED_USE: { case AUX_FUNC::DISABLE_AIRSPEED_USE: {