AP_Periph: limit peripheral mag to 25Hz by default

we only read mag on the vehicles at 10Hz. Some magnetometers were
reporting data at 500Hz (see MMC5xx3 driver)

by sampling more slowly the data is accumulated and averaged on the
node which saves a lot of bandwidth
This commit is contained in:
Andrew Tridgell 2023-03-06 20:57:31 +11:00 committed by Tom Pittenger
parent 3c65b5e5a0
commit 2781f65d56

View File

@ -73,6 +73,10 @@ extern AP_Periph_FW periph;
#endif
#endif
#ifndef AP_PERIPH_MAG_MAX_RATE
#define AP_PERIPH_MAG_MAX_RATE 25U
#endif
#define DEBUG_PRINTS 0
#define DEBUG_PKTS 0
#if DEBUG_PRINTS
@ -1777,6 +1781,15 @@ void AP_Periph_FW::can_mag_update(void)
if (!compass.available()) {
return;
}
#if AP_PERIPH_MAG_MAX_RATE > 0
// don't flood the bus with very high rate magnetometers
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_mag_update_ms < (1000U / AP_PERIPH_MAG_MAX_RATE)) {
return;
}
#endif
compass.read();
#if AP_PERIPH_PROBE_CONTINUOUS
if (compass.get_count() == 0) {