Copter: autotune adjustment for large copters
This commit is contained in:
parent
8da58226ae
commit
8e790d3f91
@ -57,15 +57,15 @@
|
||||
#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
|
||||
#define AUTOTUNE_PI_RATIO_FINAL 1.0f // I is set 1x P after testing
|
||||
#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f // I is set 1x P after testing
|
||||
#define AUTOTUNE_RD_MAX 0.050f // maximum Rate D value
|
||||
#define AUTOTUNE_RD_MAX 0.200f // maximum Rate D value
|
||||
#define AUTOTUNE_RLPF_MIN 1.0f // minimum Rate Yaw filter value
|
||||
#define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value
|
||||
#define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value
|
||||
#define AUTOTUNE_RP_MAX 2.0f // maximum Rate P value
|
||||
#define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value
|
||||
#define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value
|
||||
#define AUTOTUNE_RP_ACCEL_MIN 36000.0f // Minimum acceleration for Roll and Pitch
|
||||
#define AUTOTUNE_Y_ACCEL_MIN 9000.0f // Minimum acceleration for Yaw
|
||||
#define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch
|
||||
#define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw
|
||||
#define AUTOTUNE_Y_FILT_FREQ 10.0f // Autotune filter frequency when testing Yaw
|
||||
#define AUTOTUNE_SUCCESS_COUNT 4 // The number of successful iterations we need to freeze at current gains
|
||||
#define AUTOTUNE_D_UP_DOWN_MARGIN 0.2f // The margin below the target that we tune D in
|
||||
|
Loading…
Reference in New Issue
Block a user