mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Compass: AK8963: don't oversample AK8963
Reduce the frequency with which MPU9250 reads AK8963 to reduce the chance of errors.
This commit is contained in:
parent
6c2ceea165
commit
2b9c46e1ff
@ -41,6 +41,10 @@
|
||||
# define I2C_MST_CLOCK_400KHZ 0x0D
|
||||
# define I2C_MST_CLOCK_258KHZ 0x08
|
||||
|
||||
#define MPUREG_I2C_SLV4_CTRL 0x34
|
||||
#define MPUREG_I2C_MST_DELAY_CTRL 0x67
|
||||
# define I2C_SLV0_DLY_EN 0x01
|
||||
|
||||
#define AK8963_I2C_ADDR 0x0c
|
||||
|
||||
#define AK8963_WIA 0x00
|
||||
@ -451,6 +455,11 @@ bool AP_AK8963_SerialBus_MPU9250::start_measurements()
|
||||
{
|
||||
const uint8_t count = sizeof(struct raw_value);
|
||||
|
||||
/* Don't sample AK8963 at MPU9250's sample rate. See MPU9250's datasheet
|
||||
* about registers below and registers 73-96, External Sensor Data */
|
||||
_write(MPUREG_I2C_SLV4_CTRL, 31);
|
||||
_write(MPUREG_I2C_MST_DELAY_CTRL, I2C_SLV0_DLY_EN);
|
||||
|
||||
/* Configure the registers from AK8963 that will be read by MPU9250's
|
||||
* master: we will get the result directly from MPU9250's registers starting
|
||||
* from MPUREG_EXT_SENS_DATA_00 when read_raw() is called */
|
||||
|
Loading…
Reference in New Issue
Block a user