diff --git a/ArduCopter/config.h b/ArduCopter/config.h index f0b9eb7be07be769cc0a30b05704276227c1a59b..a54ef6982db5011161cbee322fd37c3e357939d8 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 @@ -571,6 +572,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 9978dcd670769a8372de43ad0d44ff20a7af468c..bba544ddfba1afefd3b816d0dd8471518269730c 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -451,7 +451,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: