Browse Source

AC_AutoTune: add conditional for constants based on build

gps-1.3.1
Bill Geyer 3 years ago committed by Bill Geyer
parent
commit
c5cbf6ce37
  1. 22
      libraries/AC_AutoTune/AC_AutoTune.cpp

22
libraries/AC_AutoTune/AC_AutoTune.cpp

@ -68,18 +68,18 @@ @@ -68,18 +68,18 @@
#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step
// ifdef is not working. Modified multi values to reflect heli requirements
#ifdef HELI_BUILD
// heli defines
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
#define AUTOTUNE_RP_ACCEL_MIN 20000.0f // Minimum acceleration for Roll and Pitch
#define AUTOTUNE_Y_ACCEL_MIN 10000.0f // Minimum acceleration for Yaw
#define AUTOTUNE_SP_BACKOFF 1.0f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
#if APM_BUILD_TYPE(APM_BUILD_Heli)
// heli defines
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
#define AUTOTUNE_RP_ACCEL_MIN 20000.0f // Minimum acceleration for Roll and Pitch
#define AUTOTUNE_Y_ACCEL_MIN 10000.0f // Minimum acceleration for Yaw
#define AUTOTUNE_SP_BACKOFF 1.0f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
#else
// Frame specific defaults
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
#define AUTOTUNE_RP_ACCEL_MIN 20000.0f // Minimum acceleration for Roll and Pitch
#define AUTOTUNE_Y_ACCEL_MIN 10000.0f // Minimum acceleration for Yaw
#define AUTOTUNE_SP_BACKOFF 1.0f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
// Frame specific defaults
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step
#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_SP_BACKOFF 0.9f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
#endif // HELI_BUILD
// second table of user settable parameters for quadplanes, this

Loading…
Cancel
Save