mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: reduce IMU SPI low speed to 1Mhz to avoid chip initialization issues
This commit is contained in:
parent
3d2fb949e0
commit
595be4d04d
|
@ -181,10 +181,10 @@ define HAL_STORAGE_SIZE 16384
|
|||
STORAGE_FLASH_PAGE 14
|
||||
|
||||
# spi devices
|
||||
SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8
|
||||
SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8
|
||||
SPIDEV mpu6000 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 4*MHZ
|
||||
SPIDEV icm20602 SPI4 DEVID1 IMU2_CS MODE3 1*MHZ 4*MHZ
|
||||
SPIDEV icm42605 SPI4 DEVID1 IMU3_CS MODE3 2*MHZ 16*MHZ
|
||||
SPIDEV icm42605 SPI4 DEVID1 IMU3_CS MODE3 1*MHZ 16*MHZ
|
||||
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue