mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: allocate channel option for loweheiser manual control
This commit is contained in:
parent
d86420f074
commit
151770f6e7
|
@ -512,6 +512,11 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
|
||||||
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:
|
||||||
|
case AUX_FUNC::LOWEHEISER_STARTER:
|
||||||
|
break;
|
||||||
|
|
||||||
|
// not really aux functions:
|
||||||
|
case AUX_FUNC::LOWEHEISER_THROTTLE:
|
||||||
break;
|
break;
|
||||||
case AUX_FUNC::AVOID_ADSB:
|
case AUX_FUNC::AVOID_ADSB:
|
||||||
case AUX_FUNC::AVOID_PROXIMITY:
|
case AUX_FUNC::AVOID_PROXIMITY:
|
||||||
|
@ -1420,6 +1425,11 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
||||||
case AUX_FUNC::SCRIPTING_8:
|
case AUX_FUNC::SCRIPTING_8:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case AUX_FUNC::LOWEHEISER_THROTTLE:
|
||||||
|
case AUX_FUNC::LOWEHEISER_STARTER:
|
||||||
|
// monitored by the library itself
|
||||||
|
break;
|
||||||
|
|
||||||
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);
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -216,6 +216,8 @@ public:
|
||||||
QRTL = 108, // QRTL mode
|
QRTL = 108, // QRTL mode
|
||||||
CUSTOM_CONTROLLER = 109,
|
CUSTOM_CONTROLLER = 109,
|
||||||
KILL_IMU3 = 110, // disable third IMU (for IMU failure testing)
|
KILL_IMU3 = 110, // disable third IMU (for IMU failure testing)
|
||||||
|
LOWEHEISER_STARTER = 111, // allows for manually running starter
|
||||||
|
|
||||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||||
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
||||||
|
|
||||||
|
@ -258,6 +260,7 @@ public:
|
||||||
MOUNT2_ROLL = 215, // mount2 roll input
|
MOUNT2_ROLL = 215, // mount2 roll input
|
||||||
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
|
||||||
|
|
||||||
// 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
|
||||||
|
|
Loading…
Reference in New Issue