AC_AttitudeControl: reduce throttle mix for manual modes

This commit is contained in:
Leonard Hall 2019-04-12 08:53:02 +09:00 committed by Randy Mackay
parent 77a7c1bdf7
commit e170beaf8c

View File

@ -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