From f2418882240625de7a25e7654e3090703991be70 Mon Sep 17 00:00:00 2001 From: unknown Date: Sat, 29 Oct 2011 20:34:21 +0900 Subject: [PATCH] TradHeli - added TUNE value 13 to allow adjusting of external gyro gain using channel 6 --- ArduCopter/ArduCopter.pde | 7 +++++++ ArduCopter/defines.h | 1 + 2 files changed, 8 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 94ad2fd033..a1247e0810 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1339,6 +1339,13 @@ static void tuning(){ g.pi_nav_lat.kP(tuning_value); g.pi_nav_lon.kP(tuning_value); break; + + #if FRAME_CONFIG == HELI_FRAME + case CH6_HELI_EXTERNAL_GYRO: + g.rc_6.set_range(1000,2000); + g.heli_ext_gyro_gain = tuning_value * 1000; + break; + #endif } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 003375460a..5d9f3525e6 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -147,6 +147,7 @@ #define CH6_NAV_P 11 #define CH6_LOITER_P 12 +#define CH6_HELI_EXTERNAL_GYRO 13 // nav byte mask // -------------