From c87b0adc293490f8f6ba1471e103db8b6e151ebd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Aug 2014 16:22:52 +1000 Subject: [PATCH] HAL_Linux: the MS5611 seems to be a bit happier at higher speed still getting some bogus data, but less --- libraries/AP_HAL_Linux/SPIDriver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/SPIDriver.cpp b/libraries/AP_HAL_Linux/SPIDriver.cpp index b2df5ac436..5e26a1da0a 100644 --- a/libraries/AP_HAL_Linux/SPIDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIDriver.cpp @@ -25,7 +25,7 @@ LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES // different SPI tables per board subtype LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_LSM9DS0_AM, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ), LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_LSM9DS0_G, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ), - LinuxSPIDeviceDriver(2, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, BBB_P9_42, 6*MHZ, 6*MHZ), + LinuxSPIDeviceDriver(2, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ), LinuxSPIDeviceDriver(2, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ), /* MPU9250 is restricted to 1MHz for non-data and interrupt registers */ LinuxSPIDeviceDriver(2, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),