mirror of https://github.com/ArduPilot/ardupilot
AP_Motor: tradheli align swash params btwn frames and fix metadata
This commit is contained in:
parent
fef085a1c8
commit
5898986b0a
|
@ -86,12 +86,112 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
|||
|
||||
// Indice 19 was used by COL_CTRL_DIR and should not be used
|
||||
|
||||
// @Group: SW1_H3_
|
||||
// @Path: AP_MotorsHeli_Swash.cpp
|
||||
AP_SUBGROUPINFO(_swashplate1, "SW1_", 20, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
|
||||
// @Param: SW_TYPE
|
||||
// @DisplayName: Swashplate 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
|
||||
|
||||
// @Group: SW2_H3_
|
||||
// @Path: AP_MotorsHeli_Swash.cpp
|
||||
// @Param: SW_COL_DIR
|
||||
// @DisplayName: Swashplate 1 Collective Control 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.
|
||||
// @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.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: SW_H3_SV1_POS
|
||||
// @DisplayName: Swashplate 1 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
|
||||
// @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
|
||||
// @Range: -180 180
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: SW_H3_PHANG
|
||||
// @DisplayName: Swashplate 1 Phase Angle Compensation
|
||||
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -30 30
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_swashplate1, "SW_", 20, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
|
||||
|
||||
// @Param: SW2_TYPE
|
||||
// @DisplayName: Swashplate 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
|
||||
// @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
|
||||
// @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
|
||||
// @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
|
||||
// @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
|
||||
// @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
|
||||
// @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
|
||||
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -30 30
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_swashplate2, "SW2_", 21, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
|
||||
|
||||
AP_GROUPEND
|
||||
|
|
|
@ -81,8 +81,58 @@ 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
|
||||
|
||||
// @Group: H3_SW_
|
||||
// @Path: AP_MotorsHeli_Swash.cpp
|
||||
// @Param: SW_TYPE
|
||||
// @DisplayName: Swashplate 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
|
||||
// @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.
|
||||
// @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.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: SW_H3_SV1_POS
|
||||
// @DisplayName: Swashplate 1 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
|
||||
// @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
|
||||
// @Range: -180 180
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: SW_H3_PHANG
|
||||
// @DisplayName: Swashplate 1 Phase Angle Compensation
|
||||
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -30 30
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_swashplate, "SW_", 20, AP_MotorsHeli_Single, AP_MotorsHeli_Swash),
|
||||
|
||||
AP_GROUPEND
|
||||
|
|
|
@ -30,28 +30,28 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = {
|
|||
AP_GROUPINFO("TYPE", 1, AP_MotorsHeli_Swash, _swashplate_type, SWASHPLATE_TYPE_H3_120),
|
||||
|
||||
// @Param: COL_DIR
|
||||
// @DisplayName: Collective Control Direction
|
||||
// @DisplayName: Swashplate Collective Control Direction
|
||||
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
|
||||
// @Values: 0:Normal,1:Reversed
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("COL_DIR", 2, AP_MotorsHeli_Swash, _swash_coll_dir, COLLECTIVE_DIRECTION_NORMAL),
|
||||
|
||||
// @Param: LIN_SVO
|
||||
// @DisplayName: Linearize swashplate servo mechanical throw
|
||||
// @DisplayName: Linearize Swashplate Servo Mechanical Throw
|
||||
// @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
|
||||
AP_GROUPINFO("LIN_SVO", 3, AP_MotorsHeli_Swash, _linear_swash_servo, 0),
|
||||
|
||||
// @Param: H3_ENABLE
|
||||
// @DisplayName: Enable generic H3 swashplate settings
|
||||
// @DisplayName: Enable Generic H3 Swashplate Settings
|
||||
// @Description: Automatically set when H3 generic swash type is selected. Do not set manually.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("H3_ENABLE", 4, AP_MotorsHeli_Swash, enable, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param: H3_SV1_POS
|
||||
// @DisplayName: servo 1 position
|
||||
// @DisplayName: Swashplate 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
|
||||
|
@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = {
|
|||
AP_GROUPINFO("H3_SV1_POS", 5, AP_MotorsHeli_Swash, _servo1_pos, -60),
|
||||
|
||||
// @Param: H3_SV2_POS
|
||||
// @DisplayName: servo 2 position
|
||||
// @DisplayName: Swashplate 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
|
||||
|
@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = {
|
|||
AP_GROUPINFO("H3_SV2_POS", 6, AP_MotorsHeli_Swash, _servo2_pos, 60),
|
||||
|
||||
// @Param: H3_SV3_POS
|
||||
// @DisplayName: servo 3 position
|
||||
// @DisplayName: Swashplate 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
|
||||
|
|
Loading…
Reference in New Issue