From e170beaf8ce2f203df19bce77b909c1b40e37779 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 12 Apr 2019 08:53:02 +0900 Subject: [PATCH] AC_AttitudeControl: reduce throttle mix for manual modes --- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 7ed931025e..e1c7a9beb3 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -36,7 +36,7 @@ #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0f // Min lean angle so that vehicle can maintain limited control #define AC_ATTITUDE_CONTROL_MIN_DEFAULT 0.1f // minimum throttle mix default -#define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.5f // manual throttle mix default +#define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.1f // manual throttle mix default #define AC_ATTITUDE_CONTROL_MAX_DEFAULT 0.5f // maximum throttle mix default #define AC_ATTITUDE_CONTROL_MAX 5.0f // maximum throttle mix default