AC_AttitudeControl: correct param ranges to accomodate TradHeli defaults

This commit is contained in:
Hwurzburg 2021-05-24 20:01:37 -05:00 committed by Randy Mackay
parent 02f6ca51bc
commit 3f4d4e45fc
2 changed files with 10 additions and 10 deletions

View File

@ -18,14 +18,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: RAT_RLL_P
// @DisplayName: Roll axis rate controller P gain
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
// @Range: 0.08 0.35
// @Range: 0.0 0.35
// @Increment: 0.005
// @User: Standard
// @Param: RAT_RLL_I
// @DisplayName: Roll axis rate controller I gain
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
// @Range: 0.01 0.6
// @Range: 0.0 0.6
// @Increment: 0.01
// @User: Standard
@ -45,14 +45,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: RAT_RLL_D
// @DisplayName: Roll axis rate controller D gain
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
// @Range: 0.001 0.03
// @Range: 0.0 0.03
// @Increment: 0.001
// @User: Standard
// @Param: RAT_RLL_VFF
// @DisplayName: Roll axis rate controller feed forward
// @Description: Roll axis rate controller feed forward
// @Range: 0 0.5
// @Range: 0.05 0.5
// @Increment: 0.001
// @User: Standard
@ -92,14 +92,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: RAT_PIT_P
// @DisplayName: Pitch axis rate controller P gain
// @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
// @Range: 0.08 0.35
// @Range: 0.0 0.35
// @Increment: 0.005
// @User: Standard
// @Param: RAT_PIT_I
// @DisplayName: Pitch axis rate controller I gain
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
// @Range: 0.01 0.6
// @Range: 0.0 0.6
// @Increment: 0.01
// @User: Standard
@ -119,14 +119,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: RAT_PIT_D
// @DisplayName: Pitch axis rate controller D gain
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
// @Range: 0.001 0.03
// @Range: 0.0 0.03
// @Increment: 0.001
// @User: Standard
// @Param: RAT_PIT_VFF
// @DisplayName: Pitch axis rate controller feed forward
// @Description: Pitch axis rate controller feed forward
// @Range: 0 0.5
// @Range: 0.05 0.5
// @Increment: 0.001
// @User: Standard
@ -173,7 +173,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: RAT_YAW_I
// @DisplayName: Yaw axis rate controller I gain
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
// @Range: 0.01 0.06
// @Range: 0.01 0.2
// @Increment: 0.01
// @User: Standard

View File

@ -140,7 +140,7 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// @Param: _ACCZ_P
// @DisplayName: Acceleration (vertical) controller P gain
// @Description: Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
// @Range: 0.500 1.500
// @Range: 0.200 1.500
// @Increment: 0.05
// @User: Standard