mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: calc_lowpass_alpha_dt: remove unused constrain
This commit is contained in:
parent
34609d327d
commit
702245f89e
@ -404,7 +404,7 @@ float calc_lowpass_alpha_dt(float dt, float cutoff_freq)
|
||||
return 1.0;
|
||||
}
|
||||
float rc = 1.0f/(M_2PI*cutoff_freq);
|
||||
return constrain_float(dt/(dt+rc), 0.0f, 1.0f);
|
||||
return dt/(dt+rc);
|
||||
}
|
||||
|
||||
#ifndef AP_MATH_FILL_NANF_USE_MEMCPY
|
||||
|
Loading…
Reference in New Issue
Block a user