mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_MotorsMulticopter: update_throttle_filter does not set throttle_in
get_throttle method now used to access filtered throttle
This commit is contained in:
parent
3fc3858fbd
commit
983d2dc97a
@ -161,9 +161,6 @@ void AP_MotorsMulticopter::update_throttle_filter()
|
||||
} else {
|
||||
_throttle_filter.reset(0.0f);
|
||||
}
|
||||
|
||||
// constrain throttle signal to 0-1000
|
||||
_throttle_control_input = constrain_float(_throttle_filter.get(),0.0f,1000.0f);
|
||||
}
|
||||
|
||||
// current_limit_max_throttle - limits maximum throttle based on current
|
||||
|
Loading…
Reference in New Issue
Block a user