mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_HAL_Linux: set higher SPI speed for Navio
We can set a higher speed on newer Linux kernels since
52469b2a38
.
The older ones will just floor the value.
This commit is contained in:
parent
a08d57149e
commit
72820303d4
@ -37,8 +37,8 @@ LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 16*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 250*KHZ, 4*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(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_BBBMINI
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
|
Loading…
Reference in New Issue
Block a user