Skip to content

Commit

Permalink
AC_AttitudeControl: Allow zero gains for Sub
Browse files Browse the repository at this point in the history
Close bluerobotics/ardusub#70
  • Loading branch information
jaxxzer authored and rmackay9 committed Apr 25, 2018
1 parent d07f8aa commit 6ae1bf4
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 6 deletions.
3 changes: 3 additions & 0 deletions libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,20 +76,23 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
// @DisplayName: Roll axis angle controller P gain
// @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
// @Range: 3.000 12.000
// @Range{Sub}: 0.0 12.000
// @User: Standard
AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),

// @Param: ANG_PIT_P
// @DisplayName: Pitch axis angle controller P gain
// @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
// @Range: 3.000 12.000
// @Range{Sub}: 0.0 12.000
// @User: Standard
AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),

// @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{Sub}: 0.0 6.000
// @User: Standard
AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),

Expand Down
12 changes: 6 additions & 6 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::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.30
// @Range: 0.0 0.30
// @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.5
// @Range: 0.0 0.5
// @Increment: 0.01
// @User: Standard

Expand Down Expand Up @@ -55,14 +55,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::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.30
// @Range: 0.0 0.30
// @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.5
// @Range: 0.0 0.5
// @Increment: 0.01
// @User: Standard

Expand Down Expand Up @@ -100,14 +100,14 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Param: RAT_YAW_P
// @DisplayName: Yaw axis rate controller P gain
// @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
// @Range: 0.10 0.50
// @Range: 0.0 0.50
// @Increment: 0.005
// @User: Standard

// @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.010 0.05
// @Range: 0.0 0.05
// @Increment: 0.01
// @User: Standard

Expand Down

0 comments on commit 6ae1bf4

Please sign in to comment.