AP_Motors: tradheli-update parameter display names

This commit is contained in:
bnsgeyer 2019-12-07 17:50:33 -05:00 committed by Randy Mackay
parent 04fcbacb9f
commit d8bd024d8f
4 changed files with 51 additions and 52 deletions

View File

@ -32,7 +32,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
// 2 was PIT_MAX which has been replaced by CYC_MAX
// @Param: COL_MIN
// @DisplayName: Collective Pitch Minimum
// @DisplayName: Minimum Collective Pitch
// @Description: Lowest possible servo position in PWM microseconds for the swashplate
// @Range: 1000 2000
// @Units: PWM
@ -41,7 +41,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
AP_GROUPINFO("COL_MIN", 3, AP_MotorsHeli, _collective_min, AP_MOTORS_HELI_COLLECTIVE_MIN),
// @Param: COL_MAX
// @DisplayName: Collective Pitch Maximum
// @DisplayName: Maximum Collective Pitch
// @Description: Highest possible servo position in PWM microseconds for the swashplate
// @Range: 1000 2000
// @Units: PWM
@ -50,7 +50,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
AP_GROUPINFO("COL_MAX", 4, AP_MotorsHeli, _collective_max, AP_MOTORS_HELI_COLLECTIVE_MAX),
// @Param: COL_MID
// @DisplayName: Collective Pitch Mid-Point
// @DisplayName: Zero-Thrust Collective Pitch
// @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
// @Range: 1000 2000
// @Units: PWM
@ -76,10 +76,9 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
// index 15 was RSC_POWER_HIGH. Do not use this index in the future.
// @Param: CYC_MAX
// @DisplayName: Cyclic Pitch Angle Max
// @Description: Maximum pitch angle of the swash plate
// @Range: 0 18000
// @Units: cdeg
// @DisplayName: Maximum Cyclic Pitch Angle
// @Description: Maximum cyclic pitch angle of the swash plate. There are no units to this parameter. This should be adjusted to get the desired cyclic blade pitch for the pitch and roll axes. Typically this should be 6-7 deg (measured blade pitch angle difference between stick centered and stick max deflection.
// @Range: 0 4500
// @Increment: 100
// @User: Standard
AP_GROUPINFO("CYC_MAX", 16, AP_MotorsHeli, _cyclic_max, AP_MOTORS_HELI_SWASH_CYCLIC_MAX),

View File

@ -60,8 +60,8 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
// Indices 13-15 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
// @Param: COL2_MIN
// @DisplayName: Collective Pitch Minimum for rear swashplate
// @Description: Lowest possible servo position in PWM microseconds for the rear swashplate
// @DisplayName: Swash 2 Minimum Collective Pitch
// @Description: Lowest possible servo position in PWM microseconds for swashplate 2
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
@ -69,8 +69,8 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
AP_GROUPINFO("COL2_MIN", 16, AP_MotorsHeli_Dual, _collective2_min, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN),
// @Param: COL2_MAX
// @DisplayName: Collective Pitch Maximum for rear swashplate
// @Description: Highest possible servo position in PWM microseconds for the rear swashplate
// @DisplayName: Swash 2 Maximum Collective Pitch
// @Description: Highest possible servo position in PWM microseconds for swashplate 2
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
AP_GROUPINFO("COL2_MAX", 17, AP_MotorsHeli_Dual, _collective2_max, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX),
// @Param: COL2_MID
// @DisplayName: Collective Pitch Mid-Point for rear swashplate
// @DisplayName: Swash 2 Zero-Thrust Collective Pitch
// @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
// @Range: 1000 2000
// @Units: PWM
@ -89,52 +89,52 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
// Indice 19 was used by COL_CTRL_DIR and should not be used
// @Param: SW_TYPE
// @DisplayName: Swashplate 1 Type
// @DisplayName: Swash 1 Type
// @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
// @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
// @User: Standard
// @Param: SW_COL_DIR
// @DisplayName: Swashplate 1 Collective Control Direction
// @DisplayName: Swash 1 Collective Direction
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
// @Values: 0:Normal,1:Reversed
// @User: Standard
// @Param: SW_LIN_SVO
// @DisplayName: Linearize Swashplate 1 Servo Mechanical Throw
// @DisplayName: Linearize Swash 1 Servos
// @Description: This linearizes the swashplate 1 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
// @Param: SW_H3_ENABLE
// @DisplayName: Swashplate 1 Enable Generic H3 Settings
// @DisplayName: Swash 1 H3 Generic Enable
// @Description: Automatically set when H3 generic swash type is selected for swashplate 1. Do not set manually.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: SW_H3_SV1_POS
// @DisplayName: Swashplate 1 Servo 1 Position
// @DisplayName: Swash 1 H3 Generic Servo 1 Position
// @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV2_POS
// @DisplayName: Swashplate 1 Servo 2 Position
// @DisplayName: Swash 1 H3 Generic Servo 2 Position
// @Description: Azimuth position on swashplate 1 for servo 2 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV3_POS
// @DisplayName: Swashplate 1 Servo 3 Position
// @DisplayName: Swash 1 H3 Generic Servo 3 Position
// @Description: Azimuth position on swashplate 1 for servo 3 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_PHANG
// @DisplayName: Swashplate 1 Phase Angle Compensation
// @DisplayName: Swash 1 H3 Generic Phase Angle Comp
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
// @Range: -30 30
// @Units: deg
@ -143,52 +143,52 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
AP_SUBGROUPINFO(_swashplate1, "SW_", 20, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
// @Param: SW2_TYPE
// @DisplayName: Swashplate 2 Type
// @DisplayName: Swash 2 Type
// @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
// @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
// @User: Standard
// @Param: SW2_COL_DIR
// @DisplayName: Swashplate 2 Collective Control Direction
// @DisplayName: Swash 2 Collective Direction
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
// @Values: 0:Normal,1:Reversed
// @User: Standard
// @Param: SW2_LIN_SVO
// @DisplayName: Linearize Swashplate 2 Servo Mechanical Throw
// @DisplayName: Linearize Swash 2 Servos
// @Description: This linearizes the swashplate 2 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
// @Param: SW2_H3_ENABLE
// @DisplayName: Swashplate 2 Enable Generic H3 Settings
// @DisplayName: Swash 2 H3 Generic Enable
// @Description: Automatically set when H3 generic swash type is selected for swashplate 2. Do not set manually.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: SW2_H3_SV1_POS
// @DisplayName: Swashplate 2 Servo 1 Position
// @DisplayName: Swash 2 H3 Generic Servo 1 Position
// @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW2_H3_SV2_POS
// @DisplayName: Swashplate 2 Servo 2 Position
// @DisplayName: Swash 2 H3 Generic Servo 2 Position
// @Description: Azimuth position on swashplate 2 for servo 2 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW2_H3_SV3_POS
// @DisplayName: Swashplate 2 Servo 3 Position
// @DisplayName: Swash 2 H3 Generic Servo 3 Position
// @Description: Azimuth position on swashplate 2 for servo 3 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW2_H3_PHANG
// @DisplayName: Swashplate 2 Phase Angle Compensation
// @DisplayName: Swash 2 H3 Generic Phase Angle Comp
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
// @Range: -30 30
// @Units: deg

View File

@ -39,7 +39,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("MODE", 2, AP_MotorsHeli_RSC, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH),
// @Param: RAMP_TIME
// @DisplayName: RSC Throttle Output Ramp Time
// @DisplayName: Throttle Ramp Time
// @Description: Time in seconds for throttle output (HeliRSC servo) to ramp from ground idle (RSC_IDLE) to flight idle throttle setting when motor interlock is enabled (throttle hold off).
// @Range: 0 60
// @Units: s
@ -64,7 +64,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("CRITICAL", 5, AP_MotorsHeli_RSC, _critical_speed, AP_MOTORS_HELI_RSC_CRITICAL),
// @Param: IDLE
// @DisplayName: RSC Throttle Output at Idle
// @DisplayName: Throttle Output at Idle
// @Description: Throttle output (HeliRSC Servo) in percent while armed but motor interlock is disabled (throttle hold on). FOR COMBUSTION ENGINES. Sets the engine ground idle throttle percentage with clutch disengaged. This must be set to zero for electric helicopters under most situations. If the ESC has an autorotation window this can be set to keep the autorotation window open in the ESC. Consult the operating manual for your ESC to set it properly for this purpose
// @Range: 0 50
// @Units: %
@ -73,7 +73,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("IDLE", 6, AP_MotorsHeli_RSC, _idle_output, AP_MOTORS_HELI_RSC_IDLE_DEFAULT),
// @Param: SLEWRATE
// @DisplayName: RSC Throttle Output Slew Rate
// @DisplayName: Throttle Slew Rate
// @Description: This controls the maximum rate at which the throttle output (HeliRSC servo) can change, as a percentage per second. A value of 100 means the throttle can change over its full range in one second. A value of zero gives unlimited slew rate.
// @Range: 0 500
// @Increment: 10
@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("SLEWRATE", 7, AP_MotorsHeli_RSC, _power_slewrate, 0),
// @Param: THRCRV_0
// @DisplayName: RSC Throttle Output at 0% collective
// @DisplayName: Throttle Curve at 0% Coll
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 0 percent collective is defined by H_COL_MIN. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to -2 degree of pitch.
// @Range: 0 100
// @Units: %
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("THRCRV_0", 8, AP_MotorsHeli_RSC, _thrcrv[0], AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT),
// @Param: THRCRV_25
// @DisplayName: RSC Throttle Output at 25% collective
// @DisplayName: Throttle Curve at 25% Coll
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 25% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 25% of 12 degrees is 3 degrees, so this setting would correspond to +1 degree of pitch.
// @Range: 0 100
// @Units: %
@ -99,7 +99,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("THRCRV_25", 9, AP_MotorsHeli_RSC, _thrcrv[1], AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT),
// @Param: THRCRV_50
// @DisplayName: RSC Throttle Output at 50% collective
// @DisplayName: Throttle Curve at 50% Coll
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 50% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 50% of 12 degrees is 6 degrees, so this setting would correspond to +4 degree of pitch.
// @Range: 0 100
// @Units: %
@ -108,7 +108,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("THRCRV_50", 10, AP_MotorsHeli_RSC, _thrcrv[2], AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT),
// @Param: THRCRV_75
// @DisplayName: RSC Throttle Output at 75% collective
// @DisplayName: Throttle Curve at 75% Coll
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 75% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 75% of 12 degrees is 9 degrees, so this setting would correspond to +7 degree of pitch.
// @Range: 0 100
// @Units: %
@ -117,7 +117,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("THRCRV_75", 11, AP_MotorsHeli_RSC, _thrcrv[3], AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT),
// @Param: THRCRV_100
// @DisplayName: RSC Throttle Output at 100% collective
// @DisplayName: Throttle Curve at 100% Coll
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to +10 degree of pitch.
// @Range: 0 100
// @Units: %
@ -126,7 +126,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("THRCRV_100", 12, AP_MotorsHeli_RSC, _thrcrv[4], AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT),
// @Param: GOV_SETPNT
// @DisplayName: Main Rotor Governor RPM Setpoint
// @DisplayName: Rotor Governor Setpoint
// @Description: Main rotor rpm setting that governor maintains when engaged. Set to the rotor rpm your helicopter runs in flight. When a speed sensor is installed the rotor governor maintains this speed. For governor operation this should be set 10 rpm higher than the actual desired headspeed to allow for governor droop
// @Range: 800 3500
// @Units: RPM
@ -135,7 +135,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("GOV_SETPNT", 13, AP_MotorsHeli_RSC, _governor_reference, AP_MOTORS_HELI_RSC_GOVERNOR_SETPNT_DEFAULT),
// @Param: GOV_DISGAG
// @DisplayName: Throttle Percentage for Governor Disengage
// @DisplayName: Governor Disengage Throttle
// @Description: Percentage of throttle where the governor will disengage to allow return to flight idle power. Typically should be set to the same value as flight idle throttle (the very lowest throttle setting on the throttle curve). The governor disengage can be disabled by setting this value to zero and using the pull-down from the governor TCGAIN to reduce power to flight idle with the collective at it's lowest throttle setting on the throttle curve.
// @Range: 0 50
// @Units: %
@ -144,7 +144,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("GOV_DISGAG", 14, AP_MotorsHeli_RSC, _governor_disengage, AP_MOTORS_HELI_RSC_GOVERNOR_DISENGAGE_DEFAULT),
// @Param: GOV_DROOP
// @DisplayName: Governor Droop Response Setting
// @DisplayName: Governor Droop Response
// @Description: Governor droop response under load, normal settings of 0-100%. Higher value is quicker response but may cause surging. Setting to zero disables the governor. Adjust this to be as aggressive as possible without getting surging or over-run on headspeed when the governor engages. Setting over 100% is allowable for some two-stage turbine engines to provide scheduling of the gas generator for proper torque response of the N2 spool
// @Range: 0 150
// @Units: %

View File

@ -71,7 +71,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
// @Param: GYR_GAIN_ACRO
// @DisplayName: External Gyro Gain for ACRO
// @DisplayName: ACRO External Gyro Gain
// @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
// @Range: 0 1000
// @Units: PWM
@ -82,52 +82,52 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// Indices 16-19 were used by RSC_PWM_MIN, RSC_PWM_MAX, RSC_PWM_REV, and COL_CTRL_DIR and should not be used
// @Param: SW_TYPE
// @DisplayName: Swashplate 1 Type
// @DisplayName: Swashplate Type
// @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
// @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
// @User: Standard
// @Param: SW_COL_DIR
// @DisplayName: Swashplate 1 Collective Control Direction
// @DisplayName: Collective Direction
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
// @Values: 0:Normal,1:Reversed
// @User: Standard
// @Param: SW_LIN_SVO
// @DisplayName: Linearize Swashplate 1 Servo Mechanical Throw
// @Description: This linearizes the swashplate 1 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @DisplayName: Linearize Swash Servos
// @Description: This linearizes the swashplate servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
// @Param: SW_H3_ENABLE
// @DisplayName: Swashplate 1 Enable Generic H3 Settings
// @Description: Automatically set when H3 generic swash type is selected for swashplate 1. Do not set manually.
// @DisplayName: H3 Generic Enable
// @Description: Automatically set when H3 generic swash type is selected for swashplate. Do not set manually.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: SW_H3_SV1_POS
// @DisplayName: Swashplate 1 Servo 1 Position
// @DisplayName: H3 Generic Servo 1 Position
// @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV2_POS
// @DisplayName: Swashplate 1 Servo 2 Position
// @Description: Azimuth position on swashplate 1 for servo 2 with the front of the heli being 0 deg
// @DisplayName: H3 Generic Servo 2 Position
// @Description: Azimuth position on swashplate for servo 2 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV3_POS
// @DisplayName: Swashplate 1 Servo 3 Position
// @Description: Azimuth position on swashplate 1 for servo 3 with the front of the heli being 0 deg
// @DisplayName: H3 Generic Servo 3 Position
// @Description: Azimuth position on swashplate for servo 3 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_PHANG
// @DisplayName: Swashplate 1 Phase Angle Compensation
// @DisplayName: H3 Generic Phase Angle Comp
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
// @Range: -30 30
// @Units: deg