From b3d20bb8aa2d885ec0ee64c935ea3eb312cf3540 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 10 Jan 2014 11:06:06 +0900 Subject: [PATCH] TradHeli: Drift mode to use heli manual throttle --- ArduCopter/config.h | 6 ++++++ ArduCopter/system.pde | 2 +- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 7c92e8c9e8..35fc966f52 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -112,6 +112,7 @@ # define HELI_ROLL_FF 0 # define HELI_YAW_FF 0 # define STABILIZE_THR THROTTLE_MANUAL_HELI + # define DRIFT_THR THROTTLE_MANUAL_HELI # define MPU6K_FILTER 10 # define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0 # define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000 @@ -520,6 +521,11 @@ # define ACRO_LEVEL_MAX_ANGLE 3000 #endif +// Drift Mode +#ifndef DRIFT_THR + # define DRIFT_THR THROTTLE_MANUAL_TILT_COMPENSATED +#endif + // Sport Mode #ifndef SPORT_YAW # define SPORT_YAW YAW_HOLD diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index d79d3a5916..f6022187d7 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -479,7 +479,7 @@ static bool set_mode(uint8_t mode) set_yaw_mode(YAW_DRIFT); set_roll_pitch_mode(ROLL_PITCH_DRIFT); set_nav_mode(NAV_NONE); - set_throttle_mode(THROTTLE_MANUAL_TILT_COMPENSATED); + set_throttle_mode(DRIFT_THR); break; case SPORT: