mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: BMM150: fix sampling time
We configure the sensor with an ODR of 30 Hz. There's no need to keep calling the update function at 100Hz.
This commit is contained in:
parent
9f09442548
commit
dd98fc75a9
@ -58,7 +58,7 @@
|
||||
#define DIG_XY2_REG 0x70
|
||||
#define DIG_XY1_REG 0x71
|
||||
|
||||
#define MEASURE_TIME_USEC 10000
|
||||
#define MEASURE_TIME_USEC 16667
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user