Copter: add AUTOTUNE_AGGR parameter

This commit is contained in:
Leonard Hall 2015-03-04 14:27:10 +09:00 committed by Randy Mackay
parent 864168e5ea
commit a9a6e8856b
2 changed files with 9 additions and 0 deletions

View File

@ -316,6 +316,7 @@ public:
k_param_acro_balance_pitch,
k_param_acro_yaw_p, // 244
k_param_autotune_axis_bitmask, // 245
k_param_autotune_aggressiveness, // 246
// 254,255: reserved
};
@ -465,6 +466,7 @@ public:
// Autotune
AP_Int8 autotune_axis_bitmask;
AP_Float autotune_aggressiveness;
// Note: keep initializers here in the same order as they are declared
// above.

View File

@ -1044,6 +1044,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(autotune_axis_bitmask, "AUTOTUNE_AXES", 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
// @Param: AUTOTUNE_AGGRESSIVENESS
// @DisplayName: autotune_aggressiveness
// @Description: autotune_aggressiveness. Defines the bounce back used to detect size of the D term.
// @Range: 0.05 0.10
// @User: Standard
GSCALAR(autotune_aggressiveness, "AUTOTUNE_AGGR", 0.05f),
AP_VAREND
};