AP_Compass: make length filter in MAG3110 optional

compile time for now, later can may become parameter
This commit is contained in:
Andrew Tridgell 2018-02-02 20:31:18 +11:00
parent 2065cc879c
commit 2067e25523

View File

@ -52,6 +52,14 @@ RUS:
*/
/*
the vector length filter can help with noise on the bus, but may
interfere with higher level processing. It should really be moved
into the AP_Compass_backend code, with a parameter to enable it.
*/
#ifndef MAG3110_ENABLE_LEN_FILTER
#define MAG3110_ENABLE_LEN_FILTER 0
#endif
// Registers
@ -199,7 +207,8 @@ void AP_Compass_MAG3110::_update()
bool ret=true;
#if MAG3110_ENABLE_LEN_FILTER
float len = raw_field.length();
if(is_zero(compass_len)) {
compass_len=len;
@ -216,6 +225,7 @@ void AP_Compass_MAG3110::_update()
compass_len = compass_len * (1-FILTER_KOEF) + len*FILTER_KOEF; // complimentary filter 1/10 on good samples
}
}
#endif
if(ret) {