mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_Compass: make length filter in MAG3110 optional
compile time for now, later can may become parameter
This commit is contained in:
parent
2065cc879c
commit
2067e25523
@ -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
|
// Registers
|
||||||
@ -200,6 +208,7 @@ void AP_Compass_MAG3110::_update()
|
|||||||
|
|
||||||
bool ret=true;
|
bool ret=true;
|
||||||
|
|
||||||
|
#if MAG3110_ENABLE_LEN_FILTER
|
||||||
float len = raw_field.length();
|
float len = raw_field.length();
|
||||||
if(is_zero(compass_len)) {
|
if(is_zero(compass_len)) {
|
||||||
compass_len=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
|
compass_len = compass_len * (1-FILTER_KOEF) + len*FILTER_KOEF; // complimentary filter 1/10 on good samples
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if(ret) {
|
if(ret) {
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user