Copter: AutoTune definition and comment changes
This commit is contained in:
parent
21cd73e877
commit
196f6cf1b7
@ -46,7 +46,7 @@
|
||||
#define AUTOTUNE_AXIS_BITMASK_YAW 4
|
||||
|
||||
#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
|
||||
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 500 // timeout for tuning mode's testing step
|
||||
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 750 // timeout for tuning mode's testing step
|
||||
#define AUTOTUNE_LEVEL_ANGLE_CD 300 // angle which qualifies as level
|
||||
#define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch
|
||||
#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
|
||||
@ -60,33 +60,33 @@
|
||||
#define AUTOTUNE_RD_MIN 0.004f // minimum Rate D value
|
||||
#define AUTOTUNE_RD_MAX 0.050f // maximum Rate D value
|
||||
#define AUTOTUNE_RLPF_MIN 1.0f // minimum Rate Yaw filter value
|
||||
#define AUTOTUNE_RLPF_MAX 10.0f // maximum 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_Y_FILT_FREQ 10.0f // Minimum acceleration for Roll and Pitch
|
||||
#define AUTOTUNE_SUCCESS_COUNT 4 // how many successful iterations we need to freeze at current gains
|
||||
#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
|
||||
#define AUTOTUNE_RD_BACKOFF 1.0f // Rate D gains are reduced to 50% of their maximum value discovered during tuning
|
||||
#define AUTOTUNE_RP_BACKOFF 1.0f // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning
|
||||
#define AUTOTUNE_SP_BACKOFF 0.9f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
|
||||
#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f // back off from maximum acceleration
|
||||
#define AUTOTUNE_ACCEL_Y_BACKOFF 0.75f // back off from maximum acceleration
|
||||
#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f // back off from maximum acceleration
|
||||
|
||||
// roll and pitch axes
|
||||
#define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 9000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
|
||||
#define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
|
||||
|
||||
// yaw axis
|
||||
#define AUTOTUNE_TARGET_ANGLE_YAW_CD 1000 // target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_RATE_YAW_CDS 3000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
|
||||
#define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500 // target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
|
||||
#define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
|
||||
#define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500 // minimum target angle during TESTING_RATE step that will cause us to move to next step
|
||||
#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step
|
||||
|
||||
// Auto Tune message ids for ground station
|
||||
#define AUTOTUNE_MESSAGE_STARTED 0
|
||||
|
Loading…
Reference in New Issue
Block a user