From aa4d4f8c24fe2f073aeb1e3ae044bf49e8c01cfc Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Sat, 8 Dec 2012 20:41:05 -0500 Subject: [PATCH] ACM: Adding Pre-Compiler Define for Stabilize Throttle Mode. --- ArduCopter/config.h | 8 +++++++- ArduCopter/system.pde | 2 +- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index ccebaf3b72..b7acf013c2 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -96,7 +96,8 @@ # define HELI_ROLL_FF 0 # define HELI_YAW_FF 0 # define RC_FAST_SPEED 125 - #endif + # define STABILIZE_THROTTLE THROTTLE_MANUAL +#endif // optical flow doesn't work in SITL yet @@ -534,6 +535,11 @@ #define EARTH_FRAME 0 #define BODY_FRAME 1 +// Stabilize Mode +#ifndef STABILIZE_THROTTLE + # define STABILIZE_THROTTLE THROTTLE_MANUAL_TILT_COMPENSATED +#endif + // Alt Hold Mode #ifndef ALT_HOLD_YAW # define ALT_HOLD_YAW YAW_HOLD diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index eca4275a85..49004829ff 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -447,7 +447,7 @@ static void set_mode(byte mode) ap.manual_attitude = true; set_yaw_mode(YAW_HOLD); set_roll_pitch_mode(ROLL_PITCH_STABLE); - set_throttle_mode(THROTTLE_MANUAL_TILT_COMPENSATED); + set_throttle_mode(STABILIZE_THROTTLE); break; case ALT_HOLD: