RC_Channel: save some bytes by excluding functions

This commit is contained in:
Peter Barker 2022-09-21 21:26:28 +10:00 committed by Peter Barker
parent f651a4b6ce
commit e9918306fd
1 changed files with 24 additions and 24 deletions

View File

@ -786,18 +786,18 @@ void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag)
#endif #endif
} }
#if AP_FENCE_ENABLED
// enable or disable the fence // enable or disable the fence
void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag)
{ {
#if AP_FENCE_ENABLED
AC_Fence *fence = AP::fence(); AC_Fence *fence = AP::fence();
if (fence == nullptr) { if (fence == nullptr) {
return; return;
} }
fence->enable(ch_flag == AuxSwitchPos::HIGH); fence->enable(ch_flag == AuxSwitchPos::HIGH);
#endif
} }
#endif
void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag)
{ {
@ -841,9 +841,9 @@ void RC_Channel::do_aux_function_generator(const AuxSwitchPos ch_flag)
} }
#endif #endif
#if HAL_SPRAYER_ENABLED
void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag)
{ {
#if HAL_SPRAYER_ENABLED
AC_Sprayer *sprayer = AP::sprayer(); AC_Sprayer *sprayer = AP::sprayer();
if (sprayer == nullptr) { if (sprayer == nullptr) {
return; return;
@ -852,8 +852,8 @@ void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag)
sprayer->run(ch_flag == AuxSwitchPos::HIGH); sprayer->run(ch_flag == AuxSwitchPos::HIGH);
// if we are disarmed the pilot must want to test the pump // if we are disarmed the pilot must want to test the pump
sprayer->test_pump((ch_flag == AuxSwitchPos::HIGH) && !hal.util->get_soft_armed()); sprayer->test_pump((ch_flag == AuxSwitchPos::HIGH) && !hal.util->get_soft_armed());
#endif // HAL_SPRAYER_ENABLED
} }
#endif // HAL_SPRAYER_ENABLED
void RC_Channel::do_aux_function_gripper(const AuxSwitchPos ch_flag) void RC_Channel::do_aux_function_gripper(const AuxSwitchPos ch_flag)
{ {
@ -968,15 +968,11 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun
bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
{ {
switch(ch_option) { switch(ch_option) {
#if AP_CAMERA_ENABLED #if AP_FENCE_ENABLED
case AUX_FUNC::CAMERA_TRIGGER:
do_aux_function_camera_trigger(ch_flag);
break;
#endif
case AUX_FUNC::FENCE: case AUX_FUNC::FENCE:
do_aux_function_fence(ch_flag); do_aux_function_fence(ch_flag);
break; break;
#endif
case AUX_FUNC::GRIPPER: case AUX_FUNC::GRIPPER:
do_aux_function_gripper(ch_flag); do_aux_function_gripper(ch_flag);
@ -1039,9 +1035,11 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
break; break;
#endif #endif
#if HAL_SPRAYER_ENABLED
case AUX_FUNC::SPRAYER: case AUX_FUNC::SPRAYER:
do_aux_function_sprayer(ch_flag); do_aux_function_sprayer(ch_flag);
break; break;
#endif
case AUX_FUNC::LOST_VEHICLE_SOUND: case AUX_FUNC::LOST_VEHICLE_SOUND:
do_aux_function_lost_vehicle_sound(ch_flag); do_aux_function_lost_vehicle_sound(ch_flag);
@ -1091,8 +1089,8 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH); AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH);
break; break;
case AUX_FUNC::DISABLE_AIRSPEED_USE: {
#if AP_AIRSPEED_ENABLED #if AP_AIRSPEED_ENABLED
case AUX_FUNC::DISABLE_AIRSPEED_USE: {
AP_Airspeed *airspeed = AP::airspeed(); AP_Airspeed *airspeed = AP::airspeed();
if (airspeed == nullptr) { if (airspeed == nullptr) {
break; break;
@ -1107,9 +1105,9 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
airspeed->force_disable_use(false); airspeed->force_disable_use(false);
break; break;
} }
#endif
break; break;
} }
#endif
case AUX_FUNC::MOTOR_ESTOP: case AUX_FUNC::MOTOR_ESTOP:
switch (ch_flag) { switch (ch_flag) {
@ -1127,16 +1125,16 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
} }
break; break;
case AUX_FUNC::VISODOM_ALIGN:
#if HAL_VISUALODOM_ENABLED #if HAL_VISUALODOM_ENABLED
case AUX_FUNC::VISODOM_ALIGN:
if (ch_flag == AuxSwitchPos::HIGH) { if (ch_flag == AuxSwitchPos::HIGH) {
AP_VisualOdom *visual_odom = AP::visualodom(); AP_VisualOdom *visual_odom = AP::visualodom();
if (visual_odom != nullptr) { if (visual_odom != nullptr) {
visual_odom->align_sensor_to_vehicle(); visual_odom->align_sensor_to_vehicle();
} }
} }
#endif
break; break;
#endif
case AUX_FUNC::EKF_POS_SOURCE: case AUX_FUNC::EKF_POS_SOURCE:
switch (ch_flag) { switch (ch_flag) {
@ -1155,8 +1153,8 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
} }
break; break;
case AUX_FUNC::OPTFLOW_CAL: {
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
case AUX_FUNC::OPTFLOW_CAL: {
AP_OpticalFlow *optflow = AP::opticalflow(); AP_OpticalFlow *optflow = AP::opticalflow();
if (optflow == nullptr) { if (optflow == nullptr) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled"); gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled");
@ -1167,9 +1165,9 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
} else { } else {
optflow->stop_calibration(); optflow->stop_calibration();
} }
#endif
break; break;
} }
#endif
#if !HAL_MINIMIZE_FEATURES #if !HAL_MINIMIZE_FEATURES
case AUX_FUNC::KILL_IMU1: case AUX_FUNC::KILL_IMU1:
@ -1181,8 +1179,12 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
break; break;
#endif // HAL_MINIMIZE_FEATURES #endif // HAL_MINIMIZE_FEATURES
case AUX_FUNC::CAM_MODE_TOGGLE: {
#if AP_CAMERA_ENABLED #if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_TRIGGER:
do_aux_function_camera_trigger(ch_flag);
break;
case AUX_FUNC::CAM_MODE_TOGGLE: {
// Momentary switch to for cycling camera modes // Momentary switch to for cycling camera modes
AP_Camera *camera = AP_Camera::get_singleton(); AP_Camera *camera = AP_Camera::get_singleton();
if (camera == nullptr) { if (camera == nullptr) {
@ -1199,12 +1201,12 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
camera->cam_mode_toggle(); camera->cam_mode_toggle();
break; break;
} }
#endif
break; break;
} }
#endif
case AUX_FUNC::RETRACT_MOUNT1: {
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
case AUX_FUNC::RETRACT_MOUNT1: {
AP_Mount *mount = AP::mount(); AP_Mount *mount = AP::mount();
if (mount == nullptr) { if (mount == nullptr) {
break; break;
@ -1220,20 +1222,18 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
mount->set_mode_to_default(0); mount->set_mode_to_default(0);
break; break;
} }
#endif
break; break;
} }
case AUX_FUNC::MOUNT_LOCK: { case AUX_FUNC::MOUNT_LOCK: {
#if HAL_MOUNT_ENABLED
AP_Mount *mount = AP::mount(); AP_Mount *mount = AP::mount();
if (mount == nullptr) { if (mount == nullptr) {
break; break;
} }
mount->set_yaw_lock(ch_flag == AuxSwitchPos::HIGH); mount->set_yaw_lock(ch_flag == AuxSwitchPos::HIGH);
#endif
break; break;
} }
#endif
case AUX_FUNC::LOG_PAUSE: { case AUX_FUNC::LOG_PAUSE: {
AP_Logger *logger = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
@ -1280,18 +1280,18 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
AP::ahrs().request_yaw_reset(); AP::ahrs().request_yaw_reset();
break; break;
#if HAL_TORQEEDO_ENABLED
// clear torqeedo error // clear torqeedo error
case AUX_FUNC::TORQEEDO_CLEAR_ERR: { case AUX_FUNC::TORQEEDO_CLEAR_ERR: {
#if HAL_TORQEEDO_ENABLED
if (ch_flag == AuxSwitchPos::HIGH) { if (ch_flag == AuxSwitchPos::HIGH) {
AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton(); AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();
if (torqeedo != nullptr) { if (torqeedo != nullptr) {
torqeedo->clear_motor_error(); torqeedo->clear_motor_error();
} }
} }
#endif
break; break;
} }
#endif
// do nothing for these functions // do nothing for these functions
case AUX_FUNC::MOUNT1_ROLL: case AUX_FUNC::MOUNT1_ROLL: