mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_HAL_ChibiOS: use faster SPI clock for BMI270 on MambaH743 and KakuteH7v2
This commit is contained in:
parent
fcbaa0969e
commit
d82ba1b7a3
@ -44,7 +44,7 @@ PB11 VTX_PWR OUTPUT HIGH GPIO(81)
|
|||||||
define RELAY2_PIN_DEFAULT 81
|
define RELAY2_PIN_DEFAULT 81
|
||||||
|
|
||||||
SPIDEV dataflash SPI1 DEVID1 SDCARD_CS MODE3 104*MHZ 104*MHZ
|
SPIDEV dataflash SPI1 DEVID1 SDCARD_CS MODE3 104*MHZ 104*MHZ
|
||||||
SPIDEV bmi270 SPI4 DEVID1 ICM20689_CS MODE3 1*MHZ 4*MHZ
|
SPIDEV bmi270 SPI4 DEVID1 ICM20689_CS MODE3 1*MHZ 10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16
|
||||||
|
|
||||||
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
||||||
|
|
||||||
|
@ -156,7 +156,7 @@ DMA_NOSHARE SPI3* SPI1*
|
|||||||
|
|
||||||
# spi devices
|
# spi devices
|
||||||
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
||||||
SPIDEV bmi270 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
SPIDEV bmi270 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16
|
||||||
SPIDEV mpu6000_2 SPI4 DEVID4 MPU6000_2_CS MODE3 1*MHZ 4*MHZ
|
SPIDEV mpu6000_2 SPI4 DEVID4 MPU6000_2_CS MODE3 1*MHZ 4*MHZ
|
||||||
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ
|
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ
|
||||||
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||||
|
Loading…
Reference in New Issue
Block a user