mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_HAL_AVR: Bugfix to SPIDriver_MPU6000 (works now)
This commit is contained in:
parent
8ffec83b73
commit
177da8ea5b
@ -17,6 +17,7 @@
|
||||
const AP_HAL_AVR::HAL_AVR& hal = AP_HAL_AVR_APM2;
|
||||
|
||||
const uint8_t _cs_pin = 53;
|
||||
const uint8_t _baro_cs_pin = 40;
|
||||
|
||||
static void register_write(uint8_t reg, uint8_t val) {
|
||||
hal.gpio->write(_cs_pin, 0);
|
||||
@ -50,6 +51,8 @@ static void mpu6k_init(void) {
|
||||
// Wake up device and select GyroZ clock (better performance)
|
||||
register_write(MPUREG_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
|
||||
hal.scheduler->delay(1);
|
||||
register_write(MPUREG_PWR_MGMT_2, 0);
|
||||
hal.scheduler->delay(1);
|
||||
// Disable I2C bus (recommended on datasheet)
|
||||
register_write(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
|
||||
hal.scheduler->delay(1);
|
||||
@ -103,6 +106,10 @@ static void setup() {
|
||||
hal.uart0->begin(115200);
|
||||
hal.uart0->printf_P(PSTR("Initializing MPU6000\r\n"));
|
||||
|
||||
/* Setup the barometer cs to stop it from holding the bus */
|
||||
hal.gpio->pinMode(_baro_cs_pin, GPIO_OUTPUT);
|
||||
hal.gpio->write(_baro_cs_pin, 1);
|
||||
|
||||
/* Setup CS pin hardware */
|
||||
hal.gpio->pinMode(_cs_pin, GPIO_OUTPUT);
|
||||
hal.gpio->write(_cs_pin, 1);
|
||||
|
Loading…
Reference in New Issue
Block a user