diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index ac886965c0..df80024536 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -88,6 +88,18 @@ #include // Battery monitor library #include // board configuration library #include +#include // Landing Gear library +#include +#include +#include +#include // Pilot input handling library +#include // Heli specific pilot input handling library + +// Configuration +#include "defines.h" +#include "config.h" + +// libraries which are dependent on #defines in defines.h and/or config.h #if SPRAYER == ENABLED #include // crop sprayer library #endif @@ -97,23 +109,10 @@ #if PARACHUTE == ENABLED #include // Parachute release library #endif -#include // Landing Gear library -#include -#include -#include #if PRECISION_LANDING == ENABLED #include #include #endif -#include // Pilot input handling library -#include // Heli specific pilot input handling library - - -// AP_HAL to Arduino compatibility layer -// Configuration -#include "defines.h" -#include "config.h" -#include "config_channels.h" // Local modules #include "Parameters.h" diff --git a/ArduSub/config.h b/ArduSub/config.h index 1c00da0331..37f9ea721c 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -27,11 +27,7 @@ /// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that /// change in your local copy of APM_Config.h. /// -#ifdef USE_CMAKE_APM_CONFIG - #include "APM_Config_cmake.h" // <== Prefer cmake config if it exists -#else - #include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER. -#endif +#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER. ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduSub/control_autotune.cpp b/ArduSub/control_autotune.cpp index 1b9d7af73c..13777c850c 100644 --- a/ArduSub/control_autotune.cpp +++ b/ArduSub/control_autotune.cpp @@ -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