mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_MotorsHeli: constrain filtered throttle
This is required because we have removed the constraint on the throttle input. This also insures that there is no lag caused by the filtered throttle straying far outside the 0 to 1 range
This commit is contained in:
parent
b4a61e6ccf
commit
9b5b6f3779
@ -356,6 +356,14 @@ void AP_MotorsHeli::reset_swash_servo(RC_Channel& servo)
|
||||
void AP_MotorsHeli::update_throttle_filter()
|
||||
{
|
||||
_throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
|
||||
|
||||
// constrain filtered throttle
|
||||
if (_throttle_filter.get() < 0.0f) {
|
||||
_throttle_filter.reset(0.0f);
|
||||
}
|
||||
if (_throttle_filter.get() > 1.0f) {
|
||||
_throttle_filter.reset(1.0f);
|
||||
}
|
||||
}
|
||||
|
||||
// reset_flight_controls - resets all controls and scalars to flight status
|
||||
|
Loading…
Reference in New Issue
Block a user