mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_AutoTune: allow high ANGLE_P gains
This commit is contained in:
parent
32a39055db
commit
742c2b034f
@ -51,7 +51,7 @@
|
||||
#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_MAX 40.0f // maximum Stab P value
|
||||
#define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value
|
||||
#define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch
|
||||
#define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw
|
||||
|
Loading…
Reference in New Issue
Block a user