mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_InertialSensor: always allow for AK8963 on MPU9250
This commit is contained in:
parent
d040318014
commit
520c7c1306
@ -421,11 +421,6 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||
// Chip reset
|
||||
uint8_t tries;
|
||||
for (tries = 0; tries<5; tries++) {
|
||||
#if HAL_COMPASS_DEFAULT != HAL_COMPASS_AK8963_MPU9250
|
||||
/* Prevent reseting if internal AK8963 is selected, because it may corrupt
|
||||
* AK8963's initialisation. */
|
||||
_register_write(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_DEVICE_RESET);
|
||||
#endif
|
||||
hal.scheduler->delay(100);
|
||||
|
||||
// Wake up device and select GyroZ clock. Note that the
|
||||
@ -450,13 +445,6 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||
|
||||
_register_write(MPUREG_PWR_MGMT_2, 0x00); // only used for wake-up in accelerometer only low power mode
|
||||
|
||||
// Disable I2C bus (recommended on datasheet)
|
||||
#if HAL_COMPASS_DEFAULT != HAL_COMPASS_AK8963_MPU9250
|
||||
/* Prevent disabling if internal AK8963 is selected. If internal AK8963 is not used
|
||||
* it's ok to disable I2C slaves*/
|
||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||
#endif
|
||||
|
||||
// used no filter of 256Hz on the sensor, then filter using
|
||||
// the 2-pole software filter
|
||||
_register_write(MPUREG_CONFIG, BITS_DLPF_CFG_256HZ_NOLPF2);
|
||||
|
Loading…
Reference in New Issue
Block a user