diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index d975bf2f1f..245e7811d4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -92,7 +92,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Param: ANG_YAW_P // @DisplayName: Yaw axis angle controller P gain // @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate - // @Range: 3.000 6.000 + // @Range: 3.000 12.000 // @Range{Sub}: 0.0 6.000 // @User: Standard AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P), diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 17a654a76d..5934a6ea61 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -46,7 +46,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_RLL_FLTT // @DisplayName: Roll axis rate controller target frequency in Hz // @Description: Roll axis rate controller target frequency in Hz - // @Range: 1 50 + // @Range: 5 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -54,7 +54,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_RLL_FLTE // @DisplayName: Roll axis rate controller error frequency in Hz // @Description: Roll axis rate controller error frequency in Hz - // @Range: 1 100 + // @Range: 0 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -62,7 +62,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_RLL_FLTD // @DisplayName: Roll axis rate controller derivative frequency in Hz // @Description: Roll axis rate controller derivative frequency in Hz - // @Range: 1 100 + // @Range: 5 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -107,7 +107,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_PIT_FLTT // @DisplayName: Pitch axis rate controller target frequency in Hz // @Description: Pitch axis rate controller target frequency in Hz - // @Range: 1 50 + // @Range: 5 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -115,7 +115,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_PIT_FLTE // @DisplayName: Pitch axis rate controller error frequency in Hz // @Description: Pitch axis rate controller error frequency in Hz - // @Range: 1 100 + // @Range: 0 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -123,7 +123,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_PIT_FLTD // @DisplayName: Pitch axis rate controller derivative frequency in Hz // @Description: Pitch axis rate controller derivative frequency in Hz - // @Range: 1 100 + // @Range: 5 100 // @Increment: 1 // @Units: Hz // @User: Standard @@ -168,7 +168,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_YAW_FLTT // @DisplayName: Yaw axis rate controller target frequency in Hz // @Description: Yaw axis rate controller target frequency in Hz - // @Range: 1 5 + // @Range: 1 50 // @Increment: 1 // @Units: Hz // @User: Standard @@ -176,7 +176,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_YAW_FLTE // @DisplayName: Yaw axis rate controller error frequency in Hz // @Description: Yaw axis rate controller error frequency in Hz - // @Range: 1 10 + // @Range: 0 20 // @Increment: 1 // @Units: Hz // @User: Standard @@ -184,7 +184,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Param: RAT_YAW_FLTD // @DisplayName: Yaw axis rate controller derivative frequency in Hz // @Description: Yaw axis rate controller derivative frequency in Hz - // @Range: 1 20 + // @Range: 5 50 // @Increment: 1 // @Units: Hz // @User: Standard