mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMulticopter: limit hover throttle
This commit is contained in:
parent
5c47f3f9e5
commit
bead957a78
|
@ -378,7 +378,8 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
|
|||
void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
||||
{
|
||||
if (_throttle_hover_learn != HOVER_LEARN_DISABLED) {
|
||||
_throttle_hover = _throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(get_throttle()-_throttle_hover);
|
||||
// we have chosen to constrain the hover throttle to be within the range reachable by the third order expo polynomial.
|
||||
_throttle_hover = constrain_float(_throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(get_throttle()-_throttle_hover), AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
#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_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_MAX 0.6875f // maximum possible hover throttle
|
||||
#define AP_MOTORS_SPIN_MIN_DEFAULT 0.15f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range
|
||||
#define AP_MOTORS_SPIN_MAX_DEFAULT 0.95f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
|
||||
#define AP_MOTORS_SPIN_ARM_DEFAULT 0.10f // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
|
||||
|
|
Loading…
Reference in New Issue