mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Filter: fixed a warning on PX4
This commit is contained in:
parent
6142eac4b4
commit
30b50a858d
@ -78,7 +78,7 @@ template <class T>
|
||||
void LowPassFilter<T>::set_cutoff_frequency(float time_step, float cutoff_freq)
|
||||
{
|
||||
// calculate alpha
|
||||
float rc = 1/(2*M_PI*cutoff_freq);
|
||||
float rc = 1/(2*(float)M_PI*cutoff_freq);
|
||||
_alpha = time_step / (time_step + rc);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user