mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Filter: dt check fix for LPF
This commit is contained in:
parent
f20a91ec95
commit
99a9a88529
@ -42,7 +42,7 @@ public:
|
||||
|
||||
// add a new raw value to the filter, retrieve the filtered result
|
||||
float apply(float sample, float cutoff_freq, float dt) {
|
||||
if (cutoff_freq <= 0.0f || dt < 0.0f) {
|
||||
if (cutoff_freq <= 0.0f || dt <= 0.0f) {
|
||||
_output = sample;
|
||||
return _output;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user