APM_Control: match parameter names with old PID controllers

this will make upgrading easier
This commit is contained in:
Andrew Tridgell 2013-05-30 22:57:49 +10:00
parent 91a04ab654
commit 3e8af05d15
3 changed files with 22 additions and 22 deletions

View File

@ -23,7 +23,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Units: seconds // @Units: seconds
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("T_CONST", 0, AP_PitchController, _tau, 0.7), AP_GROUPINFO("TCONST", 0, AP_PitchController, _tau, 0.5f),
// @Param: K_P // @Param: K_P
// @DisplayName: Proportional Gain // @DisplayName: Proportional Gain
@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Range: 0.1 1.0 // @Range: 0.1 1.0
// @Increment: 0.1 // @Increment: 0.1
// @User: User // @User: User
AP_GROUPINFO("K_P", 1, AP_PitchController, _K_P, 0.4), AP_GROUPINFO("P", 1, AP_PitchController, _K_P, 0.4f),
// @Param: K_D // @Param: K_D
// @DisplayName: Damping Gain // @DisplayName: Damping Gain
@ -39,7 +39,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Range: 0 0.1 // @Range: 0 0.1
// @Increment: 0.01 // @Increment: 0.01
// @User: User // @User: User
AP_GROUPINFO("K_D", 2, AP_PitchController, _K_D, 0.0), AP_GROUPINFO("D", 2, AP_PitchController, _K_D, 0.0f),
// @Param: K_I // @Param: K_I
// @DisplayName: Integrator Gain // @DisplayName: Integrator Gain
@ -47,7 +47,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Range: 0 0.5 // @Range: 0 0.5
// @Increment: 0.05 // @Increment: 0.05
// @User: User // @User: User
AP_GROUPINFO("K_I", 3, AP_PitchController, _K_I, 0.0), AP_GROUPINFO("I", 3, AP_PitchController, _K_I, 0.0f),
// @Param: RMAX_U // @Param: RMAX_U
// @DisplayName: Pitch up max rate // @DisplayName: Pitch up max rate
@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Units: degrees/second // @Units: degrees/second
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX_U", 4, AP_PitchController, _max_rate_pos, 0.0), AP_GROUPINFO("RMAX_U", 4, AP_PitchController, _max_rate_pos, 0.0f),
// @Param: RMAX_D // @Param: RMAX_D
// @DisplayName: Pitch down max rate // @DisplayName: Pitch down max rate
@ -65,7 +65,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Units: degrees/second // @Units: degrees/second
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX_D", 5, AP_PitchController, _max_rate_neg, 0.0), AP_GROUPINFO("RMAX_D", 5, AP_PitchController, _max_rate_neg, 0.0f),
// @Param: K_RLL // @Param: K_RLL
// @DisplayName: Roll compensation // @DisplayName: Roll compensation
@ -73,7 +73,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Range: 0.7 1.5 // @Range: 0.7 1.5
// @Increment: 0.05 // @Increment: 0.05
// @User: User // @User: User
AP_GROUPINFO("K_RLL", 6, AP_PitchController, _roll_ff, 1.0), AP_GROUPINFO("K_RLL", 6, AP_PitchController, _roll_ff, 1.0f),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -22,7 +22,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Units: seconds // @Units: seconds
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("T_CONST", 0, AP_RollController, _tau, 0.7), AP_GROUPINFO("TCONST", 0, AP_RollController, _tau, 0.5f),
// @Param: K_P // @Param: K_P
// @DisplayName: Proportional Gain // @DisplayName: Proportional Gain
@ -30,7 +30,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Range: 0.1 1.0 // @Range: 0.1 1.0
// @Increment: 0.1 // @Increment: 0.1
// @User: User // @User: User
AP_GROUPINFO("K_P", 1, AP_RollController, _K_P, 0.4), AP_GROUPINFO("P", 1, AP_RollController, _K_P, 0.4f),
// @Param: K_D // @Param: K_D
// @DisplayName: Damping Gain // @DisplayName: Damping Gain
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Range: 0 0.1 // @Range: 0 0.1
// @Increment: 0.01 // @Increment: 0.01
// @User: User // @User: User
AP_GROUPINFO("K_D", 2, AP_RollController, _K_D, 0.0), AP_GROUPINFO("D", 2, AP_RollController, _K_D, 0.0f),
// @Param: K_I // @Param: K_I
// @DisplayName: Integrator Gain // @DisplayName: Integrator Gain
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Range: 0 1.0 // @Range: 0 1.0
// @Increment: 0.05 // @Increment: 0.05
// @User: User // @User: User
AP_GROUPINFO("K_I", 3, AP_RollController, _K_I, 0.0), AP_GROUPINFO("I", 3, AP_RollController, _K_I, 0.0f),
// @Param: RMAX // @Param: RMAX
// @DisplayName: Maximum Roll Rate // @DisplayName: Maximum Roll Rate
@ -55,7 +55,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Units: degrees/second // @Units: degrees/second
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX", 4, AP_RollController, _max_rate, 0), AP_GROUPINFO("RMAX", 4, AP_RollController, _max_rate, 0),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -17,33 +17,33 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = { const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = {
// @Param: K_A // @Param: SLIP
// @DisplayName: Sideslip control gain // @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 K_D is tuned and the K_I integrator gain has been set. Set this gain to zero if only yaw damping is required. // @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.
// @Range: 0 4 // @Range: 0 4
// @Increment: 0.25 // @Increment: 0.25
AP_GROUPINFO("K_A", 0, AP_YawController, _K_A, 0), AP_GROUPINFO("SLIP", 0, AP_YawController, _K_A, 0),
// @Param: K_I // @Param: INT
// @DisplayName: Sidelsip control integrator // @DisplayName: Sidelsip 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: 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.
// @Range: 0 2 // @Range: 0 2
// @Increment: 0.25 // @Increment: 0.25
AP_GROUPINFO("K_I", 1, AP_YawController, _K_I, 0), AP_GROUPINFO("INT", 1, AP_YawController, _K_I, 0),
// @Param: K_D // @Param: DAMP
// @DisplayName: Yaw damping // @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 K_A and K_I gains at zero. // @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.
// @Range: 0 2 // @Range: 0 2
// @Increment: 0.25 // @Increment: 0.25
AP_GROUPINFO("K_D", 2, AP_YawController, _K_D, 0), AP_GROUPINFO("DAMP", 2, AP_YawController, _K_D, 0),
// @Param: K_RLL // @Param: RLL
// @DisplayName: Yaw coordination gain // @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: 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.
// @Range: 0.8 1.2 // @Range: 0.8 1.2
// @Increment: 0.05 // @Increment: 0.05
AP_GROUPINFO("K_RLL", 3, AP_YawController, _K_FF, 1), AP_GROUPINFO("RLL", 3, AP_YawController, _K_FF, 1),
AP_GROUPEND AP_GROUPEND
}; };