Browse Source

HAL_ChibiOS: adjust SPI clock rates on FMUv4

this prevents some timing errors on the IMUs
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
7e44b06440
  1. 4
      libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat

4
libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat

@ -143,8 +143,8 @@ PE15 MAG_CS CS @@ -143,8 +143,8 @@ PE15 MAG_CS CS
# of ArduPilot so users don't need to re-do their accel and compass calibrations
# when moving to ChibiOS
SPIDEV ms5611_int SPI2 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV mpu9250 SPI1 DEVID4 MPU9250_CS MODE3 1*MHZ 8*MHZ
SPIDEV icm20608 SPI1 DEVID6 20608_CS MODE3 1*MHZ 8*MHZ
SPIDEV mpu9250 SPI1 DEVID4 MPU9250_CS MODE3 2*MHZ 4*MHZ
SPIDEV icm20608 SPI1 DEVID6 20608_CS MODE3 2*MHZ 8*MHZ
SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
SPIDEV lis3mdl SPI1 DEVID5 MAG_CS MODE3 500*KHZ 500*KHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ

Loading…
Cancel
Save