RC_Channel: remove AUX_FUNC entries based on feature defines

This commit is contained in:
Peter Barker 2024-03-07 21:04:28 +11:00 committed by Peter Barker
parent 3dd44dd8e0
commit b09e546fce

View File

@ -59,6 +59,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_VideoTX/AP_VideoTX.h> #include <AP_VideoTX/AP_VideoTX.h>
#include <AP_Torqeedo/AP_Torqeedo.h> #include <AP_Torqeedo/AP_Torqeedo.h>
#include <AP_Vehicle/AP_Vehicle_Type.h> #include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Parachute/AP_Parachute_config.h>
#define SWITCH_DEBOUNCE_TIME_MS 200 #define SWITCH_DEBOUNCE_TIME_MS 200
const AP_Param::GroupInfo RC_Channel::var_info[] = { 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 // init channel options
switch (ch_option) { switch (ch_option) {
// the following functions do not need to be initialised: // the following functions do not need to be initialised:
#if AP_ARMING_ENABLED
case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM:
case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM_AIRMODE:
#endif
#if AP_BATTERY_ENABLED #if AP_BATTERY_ENABLED
case AUX_FUNC::BATTERY_MPPT_ENABLE: case AUX_FUNC::BATTERY_MPPT_ENABLE:
#endif #endif
#if AP_CAMERA_ENABLED #if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_TRIGGER: case AUX_FUNC::CAMERA_TRIGGER:
#endif #endif
#if AP_MISSION_ENABLED
case AUX_FUNC::CLEAR_WP: case AUX_FUNC::CLEAR_WP:
#endif
case AUX_FUNC::COMPASS_LEARN: case AUX_FUNC::COMPASS_LEARN:
#if AP_ARMING_ENABLED
case AUX_FUNC::DISARM: case AUX_FUNC::DISARM:
#endif
case AUX_FUNC::DO_NOTHING: case AUX_FUNC::DO_NOTHING:
#if AP_LANDINGGEAR_ENABLED #if AP_LANDINGGEAR_ENABLED
case AUX_FUNC::LANDING_GEAR: 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 #if HAL_VISUALODOM_ENABLED
case AUX_FUNC::VISODOM_ALIGN: case AUX_FUNC::VISODOM_ALIGN:
#endif #endif
#if AP_AHRS_ENABLED
case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_LANE_SWITCH:
case AUX_FUNC::EKF_YAW_RESET: case AUX_FUNC::EKF_YAW_RESET:
#endif
#if HAL_GENERATOR_ENABLED #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 #endif
#if AP_AHRS_ENABLED
case AUX_FUNC::EKF_POS_SOURCE: case AUX_FUNC::EKF_POS_SOURCE:
#endif
#if HAL_TORQEEDO_ENABLED #if HAL_TORQEEDO_ENABLED
case AUX_FUNC::TORQEEDO_CLEAR_ERR: case AUX_FUNC::TORQEEDO_CLEAR_ERR:
#endif #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_PITCH:
case AUX_FUNC::MOUNT2_YAW: case AUX_FUNC::MOUNT2_YAW:
#endif #endif
#if HAL_GENERATOR_ENABLED
case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::LOWEHEISER_STARTER:
#endif
#if COMPASS_CAL_ENABLED
case AUX_FUNC::MAG_CAL: case AUX_FUNC::MAG_CAL:
#endif
#if AP_CAMERA_ENABLED #if AP_CAMERA_ENABLED
case AUX_FUNC::CAMERA_IMAGE_TRACKING: case AUX_FUNC::CAMERA_IMAGE_TRACKING:
#endif #endif
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
case AUX_FUNC::MOUNT_LRF_ENABLE: case AUX_FUNC::MOUNT_LRF_ENABLE:
#endif
#if HAL_GENERATOR_ENABLED
case AUX_FUNC::LOWEHEISER_THROTTLE:
#endif #endif
break; break;
// not really aux functions:
case AUX_FUNC::LOWEHEISER_THROTTLE:
break;
#if HAL_ADSB_ENABLED #if HAL_ADSB_ENABLED
case AUX_FUNC::AVOID_ADSB: case AUX_FUNC::AVOID_ADSB:
#endif #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_IMU2:
case AUX_FUNC::KILL_IMU3: case AUX_FUNC::KILL_IMU3:
#endif #endif
#if AP_MISSION_ENABLED
case AUX_FUNC::MISSION_RESET: case AUX_FUNC::MISSION_RESET:
#endif
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 #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 #if HAL_SPRAYER_ENABLED
case AUX_FUNC::SPRAYER: case AUX_FUNC::SPRAYER:
#endif #endif
#if AP_AIRSPEED_ENABLED
case AUX_FUNC::DISABLE_AIRSPEED_USE: case AUX_FUNC::DISABLE_AIRSPEED_USE:
#endif
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:
@ -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_AUTO_FOCUS:
case AUX_FUNC::CAMERA_LENS: case AUX_FUNC::CAMERA_LENS:
#endif #endif
#if AP_AHRS_ENABLED
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;
#endif
default: default:
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n", GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
(unsigned)(this->ch_in+1), (unsigned)ch_option); (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 #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
const RC_Channel::LookupTable RC_Channel::lookuptable[] = { const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
#if AP_MISSION_ENABLED
{ AUX_FUNC::SAVE_WP,"SaveWaypoint"}, { AUX_FUNC::SAVE_WP,"SaveWaypoint"},
#endif
#if AP_CAMERA_ENABLED
{ AUX_FUNC::CAMERA_TRIGGER,"CameraTrigger"}, { AUX_FUNC::CAMERA_TRIGGER,"CameraTrigger"},
#endif
#if AP_RANGEFINDER_ENABLED
{ AUX_FUNC::RANGEFINDER,"Rangefinder"}, { AUX_FUNC::RANGEFINDER,"Rangefinder"},
#endif
#if AP_FENCE_ENABLED
{ AUX_FUNC::FENCE,"Fence"}, { AUX_FUNC::FENCE,"Fence"},
#endif
#if HAL_SPRAYER_ENABLED
{ AUX_FUNC::SPRAYER,"Sprayer"}, { AUX_FUNC::SPRAYER,"Sprayer"},
#endif
#if HAL_PARACHUTE_ENABLED
{ AUX_FUNC::PARACHUTE_ENABLE,"ParachuteEnable"}, { AUX_FUNC::PARACHUTE_ENABLE,"ParachuteEnable"},
{ AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"}, { AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"},
{ AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"}, { AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"},
#endif
#if AP_MISSION_ENABLED
{ AUX_FUNC::MISSION_RESET,"MissionReset"}, { AUX_FUNC::MISSION_RESET,"MissionReset"},
#endif
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
{ AUX_FUNC::RETRACT_MOUNT1,"RetractMount1"}, { AUX_FUNC::RETRACT_MOUNT1,"RetractMount1"},
{ AUX_FUNC::RETRACT_MOUNT2,"RetractMount2"}, { AUX_FUNC::RETRACT_MOUNT2,"RetractMount2"},
#endif #endif
#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED
{ AUX_FUNC::RELAY,"Relay1"}, { AUX_FUNC::RELAY,"Relay1"},
#endif
{ AUX_FUNC::MOTOR_ESTOP,"MotorEStop"}, { AUX_FUNC::MOTOR_ESTOP,"MotorEStop"},
{ AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"}, { AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"},
#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED
{ AUX_FUNC::RELAY2,"Relay2"}, { AUX_FUNC::RELAY2,"Relay2"},
{ AUX_FUNC::RELAY3,"Relay3"}, { AUX_FUNC::RELAY3,"Relay3"},
{ AUX_FUNC::RELAY4,"Relay4"}, { AUX_FUNC::RELAY4,"Relay4"},
#endif
{ AUX_FUNC::PRECISION_LOITER,"PrecisionLoiter"}, { AUX_FUNC::PRECISION_LOITER,"PrecisionLoiter"},
{ AUX_FUNC::AVOID_PROXIMITY,"AvoidProximity"}, { AUX_FUNC::AVOID_PROXIMITY,"AvoidProximity"},
#if AP_WINCH_ENABLED
{ AUX_FUNC::WINCH_ENABLE,"WinchEnable"}, { AUX_FUNC::WINCH_ENABLE,"WinchEnable"},
{ AUX_FUNC::WINCH_CONTROL,"WinchControl"}, { AUX_FUNC::WINCH_CONTROL,"WinchControl"},
#endif
#if AP_MISSION_ENABLED
{ AUX_FUNC::CLEAR_WP,"ClearWaypoint"}, { AUX_FUNC::CLEAR_WP,"ClearWaypoint"},
#endif
{ AUX_FUNC::COMPASS_LEARN,"CompassLearn"}, { AUX_FUNC::COMPASS_LEARN,"CompassLearn"},
{ AUX_FUNC::SAILBOAT_TACK,"SailboatTack"}, { AUX_FUNC::SAILBOAT_TACK,"SailboatTack"},
#if AP_GPS_ENABLED
{ AUX_FUNC::GPS_DISABLE,"GPSDisable"}, { AUX_FUNC::GPS_DISABLE,"GPSDisable"},
{ AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"}, { AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"},
#endif
#if AP_AIRSPEED_ENABLED
{ AUX_FUNC::DISABLE_AIRSPEED_USE,"DisableAirspeedUse"}, { AUX_FUNC::DISABLE_AIRSPEED_USE,"DisableAirspeedUse"},
#endif
#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED
{ AUX_FUNC::RELAY5,"Relay5"}, { AUX_FUNC::RELAY5,"Relay5"},
{ AUX_FUNC::RELAY6,"Relay6"}, { AUX_FUNC::RELAY6,"Relay6"},
#endif
{ AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"}, { AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"},
{ AUX_FUNC::SURFACE_TRACKING,"SurfaceTracking"}, { AUX_FUNC::SURFACE_TRACKING,"SurfaceTracking"},
#if HAL_RUNCAM_ENABLED
{ AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"}, { AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"},
{ AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"}, { AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"},
#endif
#if HAL_VISUALODOM_ENABLED
{ AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"}, { AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"},
#endif
{ AUX_FUNC::AIRMODE, "AirMode"}, { AUX_FUNC::AIRMODE, "AirMode"},
#if AP_CAMERA_ENABLED
{ AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"}, { AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"},
#endif
#if HAL_GENERATOR_ENABLED
{ AUX_FUNC::GENERATOR,"Generator"}, { AUX_FUNC::GENERATOR,"Generator"},
#endif
#if AP_BATTERY_ENABLED
{ AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"}, { AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"},
#endif
#if AP_AIRSPEED_AUTOCAL_ENABLE
{ AUX_FUNC::ARSPD_CALIBRATE,"Calibrate Airspeed"}, { AUX_FUNC::ARSPD_CALIBRATE,"Calibrate Airspeed"},
#endif
#if HAL_TORQEEDO_ENABLED
{ AUX_FUNC::TORQEEDO_CLEAR_ERR, "Torqeedo Clear Err"}, { AUX_FUNC::TORQEEDO_CLEAR_ERR, "Torqeedo Clear Err"},
#endif
{ AUX_FUNC::EMERGENCY_LANDING_EN, "Emergency Landing"}, { AUX_FUNC::EMERGENCY_LANDING_EN, "Emergency Landing"},
{ AUX_FUNC::WEATHER_VANE_ENABLE, "Weathervane"}, { AUX_FUNC::WEATHER_VANE_ENABLE, "Weathervane"},
{ AUX_FUNC::TURBINE_START, "Turbine Start"}, { AUX_FUNC::TURBINE_START, "Turbine Start"},
{ AUX_FUNC::FFT_NOTCH_TUNE, "FFT Notch Tuning"}, { AUX_FUNC::FFT_NOTCH_TUNE, "FFT Notch Tuning"},
#if HAL_MOUNT_ENABLED
{ AUX_FUNC::MOUNT_LOCK, "MountLock"}, { AUX_FUNC::MOUNT_LOCK, "MountLock"},
#endif
#if HAL_LOGGING_ENABLED
{ AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"}, { AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"},
#endif
#if AP_CAMERA_ENABLED
{ AUX_FUNC::CAMERA_REC_VIDEO, "Camera Record Video"}, { AUX_FUNC::CAMERA_REC_VIDEO, "Camera Record Video"},
{ AUX_FUNC::CAMERA_ZOOM, "Camera Zoom"}, { AUX_FUNC::CAMERA_ZOOM, "Camera Zoom"},
{ AUX_FUNC::CAMERA_MANUAL_FOCUS, "Camera Manual Focus"}, { AUX_FUNC::CAMERA_MANUAL_FOCUS, "Camera Manual Focus"},
{ AUX_FUNC::CAMERA_AUTO_FOCUS, "Camera Auto Focus"}, { AUX_FUNC::CAMERA_AUTO_FOCUS, "Camera Auto Focus"},
{ AUX_FUNC::CAMERA_IMAGE_TRACKING, "Camera Image Tracking"}, { AUX_FUNC::CAMERA_IMAGE_TRACKING, "Camera Image Tracking"},
{ AUX_FUNC::CAMERA_LENS, "Camera Lens"}, { AUX_FUNC::CAMERA_LENS, "Camera Lens"},
#endif
#if HAL_MOUNT_ENABLED
{ AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"}, { AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"},
#endif
}; };
/* lookup the announcement for switch change */ /* 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 bool RC_Channel::init_position_on_first_radio_read(AUX_FUNC func) const
{ {
switch (func) { switch (func) {
#if AP_ARMING_ENABLED
case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM:
case AUX_FUNC::ARM_EMERGENCY_STOP: case AUX_FUNC::ARM_EMERGENCY_STOP:
#endif
#if HAL_PARACHUTE_ENABLED
case AUX_FUNC::PARACHUTE_RELEASE: case AUX_FUNC::PARACHUTE_RELEASE:
#endif
// we do not want to process // we do not want to process
return true; return true;
@ -1408,12 +1483,14 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
break; break;
#endif #endif
#if AP_MISSION_ENABLED
case AUX_FUNC::CLEAR_WP: case AUX_FUNC::CLEAR_WP:
do_aux_function_clear_wp(ch_flag); do_aux_function_clear_wp(ch_flag);
break; break;
case AUX_FUNC::MISSION_RESET: case AUX_FUNC::MISSION_RESET:
do_aux_function_mission_reset(ch_flag); do_aux_function_mission_reset(ch_flag);
break; break;
#endif
#if HAL_ADSB_ENABLED #if HAL_ADSB_ENABLED
case AUX_FUNC::AVOID_ADSB: 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); do_aux_function_lost_vehicle_sound(ch_flag);
break; break;
#if AP_ARMING_ENABLED
case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM:
do_aux_function_armdisarm(ch_flag); do_aux_function_armdisarm(ch_flag);
break; 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); AP::arming().disarm(AP_Arming::Method::AUXSWITCH);
} }
break; break;
#endif
case AUX_FUNC::COMPASS_LEARN: case AUX_FUNC::COMPASS_LEARN:
if (ch_flag == AuxSwitchPos::HIGH) { if (ch_flag == AuxSwitchPos::HIGH) {
@ -1734,6 +1813,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
break; break;
} }
#if AP_AHRS_ENABLED
case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_LANE_SWITCH:
// used to test emergency lane switch // used to test emergency lane switch
AP::ahrs().check_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 #endif
break; break;
} }
#endif // AP_AHRS_ENABLED
#if HAL_TORQEEDO_ENABLED #if HAL_TORQEEDO_ENABLED
// clear torqeedo error // clear torqeedo error
@ -1766,12 +1846,15 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
#endif #endif
// do nothing for these functions // do nothing for these functions
#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
#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:
@ -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_6:
case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_7:
case AUX_FUNC::SCRIPTING_8: case AUX_FUNC::SCRIPTING_8:
#endif
break; break;
#if HAL_GENERATOR_ENABLED
case AUX_FUNC::LOWEHEISER_THROTTLE: case AUX_FUNC::LOWEHEISER_THROTTLE:
case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::LOWEHEISER_STARTER:
// monitored by the library itself // monitored by the library itself
break; break;
#endif
default: default:
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);