Sub: Changes to match Copter updates

This commit is contained in:
Rustom Jehangir 2016-02-20 11:32:42 -08:00 committed by Andrew Tridgell
parent 65a1d4fca1
commit 1d0ddcc270
3 changed files with 16 additions and 21 deletions

View File

@ -88,6 +88,18 @@
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library #include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library #include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_Frsky_Telem/AP_Frsky_Telem.h> #include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_RPM/AP_RPM.h>
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AC_InputManager/AC_InputManager_Heli.h> // 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 #if SPRAYER == ENABLED
#include <AC_Sprayer/AC_Sprayer.h> // crop sprayer library #include <AC_Sprayer/AC_Sprayer.h> // crop sprayer library
#endif #endif
@ -97,23 +109,10 @@
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
#include <AP_Parachute/AP_Parachute.h> // Parachute release library #include <AP_Parachute/AP_Parachute.h> // Parachute release library
#endif #endif
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_RPM/AP_RPM.h>
#if PRECISION_LANDING == ENABLED #if PRECISION_LANDING == ENABLED
#include <AC_PrecLand/AC_PrecLand.h> #include <AC_PrecLand/AC_PrecLand.h>
#include <AP_IRLock/AP_IRLock.h> #include <AP_IRLock/AP_IRLock.h>
#endif #endif
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AC_InputManager/AC_InputManager_Heli.h> // 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 // Local modules
#include "Parameters.h" #include "Parameters.h"

View File

@ -27,11 +27,7 @@
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that /// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
/// change in your local copy of APM_Config.h. /// change in your local copy of APM_Config.h.
/// ///
#ifdef USE_CMAKE_APM_CONFIG #include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
#else
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////

View File

@ -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_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_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_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_MIN 1.0f // minimum Rate Yaw filter value
#define AUTOTUNE_RLPF_MAX 5.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_MIN 0.01f // minimum Rate P value
#define AUTOTUNE_RP_MAX 2.0f // maximum 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 20.0f // maximum Stab P value
#define AUTOTUNE_SP_MIN 0.5f // 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_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch
#define AUTOTUNE_Y_ACCEL_MIN 9000.0f // Minimum acceleration for Yaw #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_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_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_D_UP_DOWN_MARGIN 0.2f // The margin below the target that we tune D in