mirror of https://github.com/ArduPilot/ardupilot
Update AP_YawController.cpp
This commit is contained in:
parent
f9aac6919c
commit
548a573803
|
@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||
|
||||
// @Param: SLIP
|
||||
// @DisplayName: Sideslip control gain
|
||||
// @Description: This is the gain from measured lateral acceleration to demanded yaw rate. It should be set to zero unless active control of sideslip is desired. This will only work effectively if there is enough fuselage side area to generate a measureable lateral acceleration when the model sideslips. Flying wings and most gliders cannot use this term. This term should only be adjusted after the basic yaw damper gain YAW2SRV_DAMP is tuned and the YAW2SRV_INT integrator gain has been set. Set this gain to zero if only yaw damping is required.
|
||||
// @Description: Gain from lateral acceleration to demanded yaw rate for aircraft with enough fuselage area to detect lateral acceleration and sideslips. Do not enable for flying wings and gliders. Actively coordinates flight more than just yaw damping. Set after YAW2SRV_DAMP and YAW2SRV_INT are tuned.
|
||||
// @Range: 0 4
|
||||
// @Increment: 0.25
|
||||
// @User: Advanced
|
||||
|
@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||
|
||||
// @Param: INT
|
||||
// @DisplayName: Sideslip control integrator
|
||||
// @Description: This is the integral gain from lateral acceleration error. This gain should only be non-zero if active control over sideslip is desired. If active control over sideslip is required then this can be set to 1.0 as a first try.
|
||||
// @Description: Integral gain from lateral acceleration error. Effectively trims rudder to eliminate long-term sideslip.
|
||||
// @Range: 0 2
|
||||
// @Increment: 0.25
|
||||
// @User: Advanced
|
||||
|
@ -42,7 +42,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||
|
||||
// @Param: DAMP
|
||||
// @DisplayName: Yaw damping
|
||||
// @Description: This is the gain from yaw rate to rudder. It acts as a damper on yaw motion. If a basic yaw damper is required, this gain term can be incremented, whilst leaving the YAW2SRV_SLIP and YAW2SRV_INT gains at zero. Note that unlike with a standard PID controller, if this damping term is zero then the integrator will also be disabled.
|
||||
// @Description: Gain from yaw rate to rudder. Most effective at yaw damping and should be tuned after KFF_RDDRMIX. Also disables YAW2SRV_INT if set to 0.
|
||||
// @Range: 0 2
|
||||
// @Increment: 0.25
|
||||
// @User: Advanced
|
||||
|
@ -50,7 +50,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||
|
||||
// @Param: RLL
|
||||
// @DisplayName: Yaw coordination gain
|
||||
// @Description: This is the gain term that is applied to the yaw rate offset calculated as required to keep the yaw rate consistent with the turn rate for a coordinated turn. The default value is 1 which will work for all models. Advanced users can use it to correct for any tendency to yaw away from or into the turn once the turn is established. Increase to make the model yaw more initially and decrease to make the model yaw less initially. If values greater than 1.1 or less than 0.9 are required then it normally indicates a problem with the airspeed calibration.
|
||||
// @Description: Gain to the yaw rate required to keep it consistent with the turn rate in a coordinated turn. Corrects for yaw tendencies after the turn is established. Increase yaw into the turn by raising. Increase yaw out of the turn by decreasing. Values outside of 0.9-1.1 range indicate airspeed calibration problems.
|
||||
// @Range: 0.8 1.2
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
|
@ -64,7 +64,7 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||
|
||||
// @Param: IMAX
|
||||
// @DisplayName: Integrator limit
|
||||
// @Description: This limits the number of centi-degrees of rudder 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 degrees, so the default value represents a 1/3rd of the total control throw which is adequate for most aircraft unless they are severely out of trim or have very limited rudder control effectiveness.
|
||||
// @Description: Limit of yaw integrator gain in centi-degrees of servo travel. Servos are assumed to have +/- 4500 centi-degrees of travel, so a value of 1500 allows trim of up to 1/3 of servo travel range.
|
||||
// @Range: 0 4500
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
|
|
Loading…
Reference in New Issue