From f5488bc447e8b1e3009474a9e2a91e65b949dfaa Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 15 Nov 2013 21:57:18 +0900 Subject: [PATCH] HAL: MPU6k and Baro SPI to 8Mhz --- libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp b/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp index d01129cae3..5f59fe6d75 100644 --- a/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp +++ b/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp @@ -29,13 +29,13 @@ void APM2SPIDeviceManager::init(void* machtnichts) { AVRDigitalSource* mpu6k_cs = new AVRDigitalSource(_BV(0), PB); /* mpu6k: run clock at 8MHz in high speed mode and 512kHz for low * speed */ - _mpu6k = new AVRSPI0DeviceDriver(mpu6k_cs, SPI0_SPCR_500kHz, SPI0_SPCR_500kHz, SPI0_SPSR_500kHz); + _mpu6k = new AVRSPI0DeviceDriver(mpu6k_cs, SPI0_SPCR_500kHz, SPI0_SPCR_8MHz, SPI0_SPSR_8MHz); _mpu6k->init(); /* ms5611 cs is on Arduino pin 40, PORTG1 */ AVRDigitalSource* ms5611_cs = new AVRDigitalSource(_BV(1), PG); /* ms5611: run clock at 8MHz */ - _ms5611 = new AVRSPI0DeviceDriver(ms5611_cs, SPI0_SPCR_500kHz, SPI0_SPCR_500kHz, SPI0_SPSR_500kHz); + _ms5611 = new AVRSPI0DeviceDriver(ms5611_cs, SPI0_SPCR_500kHz, SPI0_SPCR_8MHz, SPI0_SPSR_8MHz); _ms5611->init(); /* optflow cs is on Arduino pin A3, PORTF3 */