Browse Source

ArduCopter: add parameter descriptions for loiter's lat and lon rate controllers

master
rmackay9 12 years ago
parent
commit
4a975d35ce
  1. 88
      ArduCopter/Parameters.pde

88
ArduCopter/Parameters.pde

@ -537,61 +537,131 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -537,61 +537,131 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: RATE_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.20
// @Range: 0.08 0.20
// @User: Standard
// @Param: RATE_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.01 0.5
// @User: Standard
// @Param: RATE_RLL_IMAX
// @DisplayName: Roll axis rate controller I gain maximum
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 500
// @Unit: PWM
// @User: Standard
// @Param: RATE_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.008
// @Range: 0.001 0.008
// @User: Standard
GGROUP(pid_rate_roll, "RATE_RLL_", AC_PID),
// @Param: RATE_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.20
// @Range: 0.08 0.20
// @User: Standard
// @Param: RATE_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.01 0.5
// @User: Standard
// @Param: RATE_PIT_IMAX
// @DisplayName: Pitch axis rate controller I gain maximum
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 500
// @Unit: PWM
// @User: Standard
// @Param: RATE_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.008
// @Range: 0.001 0.008
// @User: Standard
GGROUP(pid_rate_pitch, "RATE_PIT_", AC_PID),
// @Param: RATE_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.150 0.250
// @Range: 0.150 0.250
// @User: Standard
// @Param: RATE_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.020
// @Range: 0.010 0.020
// @User: Standard
// @Param: RATE_YAW_IMAX
// @DisplayName: Yaw axis rate controller I gain maximum
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 500
// @Unit: PWM
// @User: Standard
// @Param: RATE_YAW_D
// @DisplayName: Yaw axis rate controller D gain
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
// @Range 0.000 0.001
// @Range: 0.000 0.001
// @User: Standard
GGROUP(pid_rate_yaw, "RATE_YAW_", AC_PID),
// @Param: LOITER_LAT_P
// @DisplayName: Loiter latitude rate controller P gain
// @Description: Loiter latitude rate controller P gain. Converts the difference between desired speed and actual speed into a lean angle in the latitude direction
// @Range: 2.000 6.000
// @User: Standard
// @Param: LOITER_LAT_I
// @DisplayName: Loiter latitude rate controller I gain
// @Description: Loiter latitude rate controller I gain. Corrects long-term difference in desired speed and actual speed in the latitude direction
// @Range: 0.020 0.060
// @User: Standard
// @Param: LOITER_LAT_IMAX
// @DisplayName: Loiter rate controller I gain maximum
// @Description: Loiter rate controller I gain maximum. Constrains the lean angle that the I gain will output
// @Range: 0 4500
// @Unit: Centi-Degrees
// @User: Standard
// @Param: LOITER_LAT_D
// @DisplayName: Loiter latitude rate controller D gain
// @Description: Loiter latitude rate controller D gain. Compensates for short-term change in desired speed vs actual speed
// @Range: 0.200 0.600
// @User: Standard
GGROUP(pid_loiter_rate_lat, "LOITER_LAT_", AC_PID),
// @Param: LOITER_LON_P
// @DisplayName: Loiter longitude rate controller P gain
// @Description: Loiter longitude rate controller P gain. Converts the difference between desired speed and actual speed into a lean angle in the longitude direction
// @Range: 2.000 6.000
// @User: Standard
// @Param: LOITER_LON_I
// @DisplayName: Loiter longitude rate controller I gain
// @Description: Loiter longitude rate controller I gain. Corrects long-term difference in desired speed and actual speed in the longitude direction
// @Range: 0.020 0.060
// @User: Standard
// @Param: LOITER_LON_IMAX
// @DisplayName: Loiter longitude rate controller I gain maximum
// @Description: Loiter longitude rate controller I gain maximum. Constrains the lean angle that the I gain will output
// @Range: 0 4500
// @Unit: Centi-Degrees
// @User: Standard
// @Param: LOITER_LON_D
// @DisplayName: Loiter longituderate controller D gain
// @Description: Loiter longitude rate controller D gain. Compensates for short-term change in desired speed vs actual speed
// @Range: 0.200 0.600
// @User: Standard
GGROUP(pid_loiter_rate_lon, "LOITER_LON_", AC_PID),
GGROUP(pid_nav_lat, "NAV_LAT_", AC_PID),

Loading…
Cancel
Save