Copter: reduce default MOT_THST_HOVER to 0.35

This commit is contained in:
Randy Mackay 2017-02-07 11:20:13 +09:00
parent c4419739c4
commit a14265359f
1 changed files with 1 additions and 1 deletions

View File

@ -13,7 +13,7 @@
#define AP_MOTORS_SPIN_WHEN_ARMED 70 // spin motors at this PWM value when armed #define AP_MOTORS_SPIN_WHEN_ARMED 70 // spin motors at this PWM value when armed
#define AP_MOTORS_YAW_HEADROOM_DEFAULT 200 #define AP_MOTORS_YAW_HEADROOM_DEFAULT 200
#define AP_MOTORS_THST_EXPO_DEFAULT 0.65f // set to 0 for linear and 1 for second order approximation #define AP_MOTORS_THST_EXPO_DEFAULT 0.65f // set to 0 for linear and 1 for second order approximation
#define AP_MOTORS_THST_HOVER_DEFAULT 0.5f // the estimated hover throttle, 0 ~ 1 #define AP_MOTORS_THST_HOVER_DEFAULT 0.35f // the estimated hover throttle, 0 ~ 1
#define AP_MOTORS_THST_HOVER_TC 10.0f // time constant used to update estimated hover throttle, 0 ~ 1 #define AP_MOTORS_THST_HOVER_TC 10.0f // time constant used to update estimated hover throttle, 0 ~ 1
#define AP_MOTORS_THST_HOVER_MIN 0.125f // minimum possible hover throttle #define AP_MOTORS_THST_HOVER_MIN 0.125f // minimum possible hover throttle
#define AP_MOTORS_THST_HOVER_MAX 0.6875f // maximum possible hover throttle #define AP_MOTORS_THST_HOVER_MAX 0.6875f // maximum possible hover throttle