mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Motors: add throttle filter input constraint from -100 to 1100
This commit is contained in:
parent
b7632194cc
commit
28731d2bdc
@ -224,7 +224,7 @@ void AP_Motors::slow_start(bool true_false)
|
|||||||
void AP_Motors::update_throttle_filter()
|
void AP_Motors::update_throttle_filter()
|
||||||
{
|
{
|
||||||
if (armed()) {
|
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 {
|
} else {
|
||||||
_throttle_filter.reset(0.0f);
|
_throttle_filter.reset(0.0f);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user