mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Filter: set output slew rate to zero when max is zero.
This commit is contained in:
parent
ae1f274919
commit
830130b8b6
@ -41,6 +41,7 @@ SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_ta
|
|||||||
float SlewLimiter::modifier(float sample, float dt)
|
float SlewLimiter::modifier(float sample, float dt)
|
||||||
{
|
{
|
||||||
if (slew_rate_max <= 0) {
|
if (slew_rate_max <= 0) {
|
||||||
|
_output_slew_rate = 0.0;
|
||||||
return 1.0;
|
return 1.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user