ArduCopter/RC_Channel: add option 219

(Transmitter Tuning)
This commit is contained in:
Luca Pescante 2023-10-07 18:43:21 +08:00 committed by Peter Barker
parent 8a4b925c71
commit 028017e38e
3 changed files with 6 additions and 0 deletions

View File

@ -128,6 +128,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::FORCEFLYING: case AUX_FUNC::FORCEFLYING:
case AUX_FUNC::CUSTOM_CONTROLLER: case AUX_FUNC::CUSTOM_CONTROLLER:
case AUX_FUNC::WEATHER_VANE_ENABLE: case AUX_FUNC::WEATHER_VANE_ENABLE:
case AUX_FUNC::TRANSMITTER_TUNING:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
break; break;
default: default:
@ -648,6 +649,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break; break;
} }
#endif #endif
case AUX_FUNC::TRANSMITTER_TUNING:
// do nothing, used in tuning.cpp for transmitter based tuning
break;
default: default:
return RC_Channel::do_aux_function(ch_option, ch_flag); return RC_Channel::do_aux_function(ch_option, ch_flag);

View File

@ -247,6 +247,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Values{Plane}: 210:Airbrakes // @Values{Plane}: 210:Airbrakes
// @Values{Rover}: 211:Walking Height // @Values{Rover}: 211:Walking Height
// @Values{Copter, Rover, Plane}: 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw // @Values{Copter, Rover, Plane}: 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw
// @Values{Copter}: 219:Transmitter Tuning
// @Values{Copter, Rover, Plane}: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 // @Values{Copter, Rover, Plane}: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8
// @User: Standard // @User: Standard
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE|AP_PARAM_FRAME_BLIMP), AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE|AP_PARAM_FRAME_BLIMP),

View File

@ -271,6 +271,7 @@ public:
MOUNT2_PITCH = 216, // mount3 pitch input MOUNT2_PITCH = 216, // mount3 pitch input
MOUNT2_YAW = 217, // mount4 yaw input MOUNT2_YAW = 217, // mount4 yaw input
LOWEHEISER_THROTTLE= 218, // allows for throttle on slider LOWEHEISER_THROTTLE= 218, // allows for throttle on slider
TRANSMITTER_TUNING = 219, // use a transmitter knob or slider for in-flight tuning
// inputs 248-249 are reserved for the Skybrush fork at // inputs 248-249 are reserved for the Skybrush fork at
// https://github.com/skybrush-io/ardupilot // https://github.com/skybrush-io/ardupilot