|
|
|
@ -92,9 +92,9 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
@@ -92,9 +92,9 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
|
|
|
|
// @Param: OPTION
|
|
|
|
|
// @DisplayName: RC input option
|
|
|
|
|
// @Description: Function assigned to this RC channel
|
|
|
|
|
// @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 83:ZigZag Auto, 84:Air Mode, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle
|
|
|
|
|
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 100:KillIMU1, 101:KillIMU2, 207:MainSail, 102:Camera Mode Toggle
|
|
|
|
|
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81:Disarm, 82:QAssist 3pos, 100:KillIMU1, 101:KillIMU2, 208:Flap, 102:Camera Mode Toggle
|
|
|
|
|
// @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 83:ZigZag Auto, 84:Air Mode, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw
|
|
|
|
|
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 100:KillIMU1, 101:KillIMU2, 207:MainSail, 102:Camera Mode Toggle, 105:GPS Disable Yaw
|
|
|
|
|
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81:Disarm, 82:QAssist 3pos, 100:KillIMU1, 101:KillIMU2, 208:Flap, 102:Camera Mode Toggle, 105:GPS Disable Yaw
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE), |
|
|
|
|
|
|
|
|
@ -473,6 +473,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
@@ -473,6 +473,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
|
|
|
|
|
case AUX_FUNC::AVOID_PROXIMITY: |
|
|
|
|
case AUX_FUNC::FENCE: |
|
|
|
|
case AUX_FUNC::GPS_DISABLE: |
|
|
|
|
case AUX_FUNC::GPS_DISABLE_YAW: |
|
|
|
|
case AUX_FUNC::GRIPPER: |
|
|
|
|
case AUX_FUNC::KILL_IMU1: |
|
|
|
|
case AUX_FUNC::KILL_IMU2: |
|
|
|
@ -522,6 +523,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
@@ -522,6 +523,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
|
|
|
|
|
{ AUX_FUNC::COMPASS_LEARN,"CompassLearn"}, |
|
|
|
|
{ AUX_FUNC::SAILBOAT_TACK,"SailboatTack"}, |
|
|
|
|
{ AUX_FUNC::GPS_DISABLE,"GPSDisable"}, |
|
|
|
|
{ AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"}, |
|
|
|
|
{ AUX_FUNC::RELAY5,"Relay5"}, |
|
|
|
|
{ AUX_FUNC::RELAY6,"Relay6"}, |
|
|
|
|
{ AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"}, |
|
|
|
@ -927,6 +929,10 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
@@ -927,6 +929,10 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
|
|
|
|
AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_FUNC::GPS_DISABLE_YAW: |
|
|
|
|
AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_FUNC::MOTOR_ESTOP: |
|
|
|
|
switch (ch_flag) { |
|
|
|
|
case AuxSwitchPos::HIGH: { |
|
|
|
|