AP_Motors: add throttle filter input constraint from -100 to 1100

This commit is contained in:
Jonathan Challinger 2015-04-23 21:35:33 -07:00 committed by Randy Mackay
parent b7632194cc
commit 28731d2bdc

View File

@ -224,7 +224,7 @@ void AP_Motors::slow_start(bool true_false)
void AP_Motors::update_throttle_filter()
{
if (armed()) {
_throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
_throttle_filter.apply(constrain_float(_throttle_in,-100,1100), 1.0f/_loop_rate);
} else {
_throttle_filter.reset(0.0f);
}