diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 3d5d26845d..86e68be260 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -42,6 +42,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 1 100 // @Increment: 1 // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID), // @Param: RAT_PIT_P @@ -79,6 +80,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 1 100 // @Increment: 1 // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID), // @Param: RAT_YAW_P @@ -116,6 +118,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 1 100 // @Increment: 1 // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID), // @Param: THR_MIX_MIN