|
|
|
@ -44,6 +44,12 @@ SPIDeviceDriver SPIDeviceManager::_device[] = {
@@ -44,6 +44,12 @@ SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
|
|
|
SPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ), |
|
|
|
|
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 250*KHZ, 5*MHZ), |
|
|
|
|
}; |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 |
|
|
|
|
SPIDeviceDriver SPIDeviceManager::_device[] = { |
|
|
|
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */ |
|
|
|
|
SPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ), |
|
|
|
|
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_MS5611, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*KHZ, 10*MHZ), |
|
|
|
|
}; |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI |
|
|
|
|
SPIDeviceDriver SPIDeviceManager::_device[] = { |
|
|
|
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */ |
|
|
|
|