AC_AttitudeControl: Fix copy paste param doc error

This commit is contained in:
Michael du Breuil 2018-10-24 10:28:45 -07:00 committed by Peter Barker
parent f67a9af339
commit 5846a54c17

View File

@ -124,8 +124,8 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f), AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f),
// @Param: RATE_Y_MAX // @Param: RATE_Y_MAX
// @DisplayName: Angular Velocity Max for Pitch // @DisplayName: Angular Velocity Max for Yaw
// @Description: Maximum angular velocity in pitch axis // @Description: Maximum angular velocity in yaw axis
// @Units: deg/s // @Units: deg/s
// @Range: 0 1080 // @Range: 0 1080
// @Increment: 1 // @Increment: 1