Filter: remove filter with double type
We are currently not using LowPassFilter2p<double> and it just generates a lot of warnings on PX4 while instantiating it due to implicitly promoting float to double: libraries/Filter/LowPassFilter2p.cpp: In instantiation of 'T DigitalBiquadFilter<T>::apply(const T&, const DigitalBiquadFilter<T>::biquad_params&) [with T = double]': libraries/Filter/LowPassFilter2p.cpp:86:41: required from 'T LowPassFilter2p<T>::apply(const T&) [with T = double]' libraries/Filter/LowPassFilter2p.cpp:98:16: required from here libraries/Filter/LowPassFilter2p.cpp:20:82: warning: implicit conversion from 'float' to 'double' to match other operand of binary expression [-Wdouble-promotion] T delay_element_0 = sample - _delay_element_1 * params.a1 - _delay_element_2 * params.a2; ^
This commit is contained in:
parent
e33aa7898a
commit
825d10c81a
@ -93,6 +93,5 @@ T LowPassFilter2p<T>::apply(const T &sample) {
|
||||
template class LowPassFilter2p<int>;
|
||||
template class LowPassFilter2p<long>;
|
||||
template class LowPassFilter2p<float>;
|
||||
template class LowPassFilter2p<double>;
|
||||
template class LowPassFilter2p<Vector2f>;
|
||||
template class LowPassFilter2p<Vector3f>;
|
||||
|
@ -88,9 +88,8 @@ LowPassFilter2p<T>::LowPassFilter2p(float sample_freq, float cutoff_freq) {
|
||||
typedef LowPassFilter2p<int> LowPassFilter2pInt;
|
||||
typedef LowPassFilter2p<long> LowPassFilter2pLong;
|
||||
typedef LowPassFilter2p<float> LowPassFilter2pFloat;
|
||||
typedef LowPassFilter2p<double> LowPassFilter2pDouble;
|
||||
typedef LowPassFilter2p<Vector2f> LowPassFilter2pVector2f;
|
||||
typedef LowPassFilter2p<Vector3f> LowPassFilter2pVector3f;
|
||||
|
||||
|
||||
#endif // LOWPASSFILTER2P_H
|
||||
#endif // LOWPASSFILTER2P_H
|
||||
|
Loading…
Reference in New Issue
Block a user