Copter: increase Autotune test time out for large copters

This commit is contained in:
Leonard Hall 2016-10-23 17:35:06 +10:30 committed by Randy Mackay
parent 8cd8f0d570
commit 71b5584d17
1 changed files with 1 additions and 1 deletions

View File

@ -42,7 +42,7 @@
#define AUTOTUNE_AXIS_BITMASK_YAW 4 #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_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 750 // timeout for tuning mode's testing step #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000 // timeout for tuning mode's testing step
#define AUTOTUNE_LEVEL_ANGLE_CD 300 // angle which qualifies as level #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_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 #define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw