mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: rename flaperon1 and flaperon2 to flaperon_left and flaperon_right
this makes it more consistent with elevons and vtails
This commit is contained in:
parent
edc9d4db5b
commit
6b3bb29398
|
@ -65,7 +65,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
|
|||
// @Param: FUNCTION
|
||||
// @DisplayName: Servo output function
|
||||
// @Description: Function assigned to this servo. Seeing this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
|
||||
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput,19:Elevator,20:ElevatorWithInput,21:Rudder,24:Flaperon1,25:Flaperon2,26:GroundSteering,27:Parachute,28:EPM,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:MotorTilt,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,68:Choke,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:tiltMotorLeft,76:tiltMotorRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle
|
||||
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput,19:Elevator,20:ElevatorWithInput,21:Rudder,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:EPM,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:MotorTilt,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,68:Choke,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:tiltMotorLeft,76:tiltMotorRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("FUNCTION", 5, SRV_Channel, function, 0),
|
||||
|
||||
|
|
|
@ -61,8 +61,8 @@ public:
|
|||
k_rudder = 21, ///< secondary rudder channel
|
||||
k_sprayer_pump = 22, ///< crop sprayer pump channel
|
||||
k_sprayer_spinner = 23, ///< crop sprayer spinner channel
|
||||
k_flaperon1 = 24, ///< flaperon, left wing
|
||||
k_flaperon2 = 25, ///< flaperon, right wing
|
||||
k_flaperon_left = 24, ///< flaperon, left wing
|
||||
k_flaperon_right = 25, ///< flaperon, right wing
|
||||
k_steering = 26, ///< ground steering, used to separate from rudder
|
||||
k_parachute_release = 27, ///< parachute release
|
||||
k_gripper = 28, ///< gripper
|
||||
|
|
|
@ -106,8 +106,8 @@ void SRV_Channel::aux_servo_function_setup(void)
|
|||
case k_dspoiler2:
|
||||
case k_rudder:
|
||||
case k_steering:
|
||||
case k_flaperon1:
|
||||
case k_flaperon2:
|
||||
case k_flaperon_left:
|
||||
case k_flaperon_right:
|
||||
case k_tiltMotorLeft:
|
||||
case k_tiltMotorRight:
|
||||
case k_elevon_left:
|
||||
|
|
Loading…
Reference in New Issue