APM_Control: fixed some documentation typos

This commit is contained in:
Andrew Tridgell 2013-09-09 10:17:21 +10:00
parent 7413c15959
commit 0918393fed
1 changed files with 3 additions and 3 deletions

View File

@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Param: T_CONST
// @DisplayName: Pitch Time Constant
// @DisplayName: Roll Time Constant
// @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
// @Range: 0.4 1.0
// @Units: seconds
@ -44,7 +44,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Param: D
// @DisplayName: Damping Gain
// @Description: This is the gain from roll rate to aileron. This adjusts the damping of the roll control loop. It has the same effect as RLL2SRV_D in the old PID controller but without the spikes in servo demands. This gain helps to reduce rolling in turbulence. It should be increased in 0.01 increments as too high a value can lead to a high frequency pitch oscillation that could overstress the airframe.
// @Description: This is the gain from roll rate to aileron. This adjusts the damping of the roll control loop. It has the same effect as RLL2SRV_D in the old PID controller but without the spikes in servo demands. This gain helps to reduce rolling in turbulence. It should be increased in 0.01 increments as too high a value can lead to a high frequency roll oscillation that could overstress the airframe.
// @Range: 0 0.1
// @Increment: 0.01
// @User: User
@ -69,7 +69,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Param: IMAX
// @DisplayName: Integrator limit
// @Description: This limits the number of degrees of aileron in centi-dgrees over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the aircraft is severely out of trim.
// @Description: This limits the number of degrees of aileron in centi-degrees over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the aircraft is severely out of trim.
// @Range: 0 4500
// @Increment: 1
// @User: Advanced