From d8fd3eadfdd1fa5d0a456ee440f5712a6a792c27 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 27 Sep 2011 07:36:12 +0800 Subject: [PATCH] heli config --- ArduCopter/APM_Config.h | 44 +++++++++++++++++++++++++++++++++++++++-- 1 file changed, 42 insertions(+), 2 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index e95fdddeb1..ccd7e5c548 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -6,11 +6,11 @@ //#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD //#define GCS_PROTOCOL GCS_PROTOCOL_NONE -//#define HIL_MODE HIL_MODE_ATTITUDE +#define HIL_MODE HIL_MODE_ATTITUDE //#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode) -#define FRAME_CONFIG QUAD_FRAME +#define FRAME_CONFIG HELI_FRAME /* options: QUAD_FRAME @@ -48,3 +48,43 @@ //#define RATE_ROLL_I 0.18 //#define RATE_PITCH_I 0.18 + + +#define AUTO_RESET_LOITER 0 +#define FRAME_CONFIG HELI_FRAME + +// DEFAULT PIDS + +// roll +#define STABILIZE_ROLL_P 0.70 +#define STABILIZE_ROLL_I 0.025 +#define STABILIZE_ROLL_D 0.04 +#define STABILIZE_ROLL_IMAX 7 + +//pitch +#define STABILIZE_PITCH_P 0.70 +#define STABILIZE_PITCH_I 0.025 +#define STABILIZE_PITCH_D 0.04 +#define STABILIZE_PITCH_IMAX 7 + +// yaw stablise +#define STABILIZE_YAW_P 0.7 +#define STABILIZE_YAW_I 0.02 +#define STABILIZE_YAW_D 0.0 + +// yaw rate +#define RATE_YAW_P 0.135 +#define RATE_YAW_I 0.0 +#define RATE_YAW_D 0.0 + +// throttle +#define THROTTLE_P 0.2 +#define THROTTLE_I 0.001 +#define THROTTLE_IMAX 100 + +// navigation +#define NAV_LOITER_P 1.1 +#define NAV_LOITER_I 0.03 +#define NAV_LOITER_D 0.02 +#define NAV_LOITER_IMAX 10 +