From 9f8f27090a64a31dace8f37dfce8388c7845ce11 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Jul 2014 18:32:38 +1000 Subject: [PATCH] HAL_Linux: MPU9250 is restricted to 1MHz for setup (see datasheet) --- libraries/AP_HAL_Linux/SPIDriver.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/SPIDriver.cpp b/libraries/AP_HAL_Linux/SPIDriver.cpp index 61f8d961d9..c4b0da321d 100644 --- a/libraries/AP_HAL_Linux/SPIDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIDriver.cpp @@ -23,7 +23,8 @@ extern const AP_HAL::HAL& hal; LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = { LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MS5611, SPI_MODE_3, 8, BBB_P9_42, 6*MHZ, 6*MHZ), LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ), - LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 6*MHZ, 20*MHZ), + /* MPU9250 is restricted to 1MHz for non-data and interrupt registers */ + LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ), LinuxSPIDeviceDriver(0, LINUX_SPI_DEVICE_LSM9DS0, SPI_MODE_0, 8, BBB_P9_17, 6*MHZ, 6*MHZ), LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_FRAM, SPI_MODE_0, 8, BBB_P8_12, 6*MHZ, 6*MHZ) };