mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: adjust external bus clock for mpu9250
this fixes an issue with fast sampling on the PH2.1 cube
This commit is contained in:
parent
93fa74518a
commit
dd59a5ff57
|
@ -132,7 +132,7 @@ SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
|||
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 4*MHZ
|
||||
SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_g SPI1 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_am SPI1 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
|
@ -144,6 +144,14 @@ SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ
|
|||
SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ
|
||||
SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ
|
||||
|
||||
# for SPI clock testing
|
||||
#SPIDEV clock500 SPI4 DEVID5 MPU_EXT_CS MODE0 500*KHZ 500*KHZ # gives 329KHz
|
||||
#SPIDEV clock1 SPI4 DEVID5 MPU_EXT_CS MODE0 1*MHZ 1*MHZ # gives 657kHz
|
||||
#SPIDEV clock2 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ # gives 1.3MHz
|
||||
#SPIDEV clock4 SPI4 DEVID5 MPU_EXT_CS MODE0 4*MHZ 4*MHZ # gives 2.6MHz
|
||||
#SPIDEV clock8 SPI4 DEVID5 MPU_EXT_CS MODE0 8*MHZ 8*MHZ # gives 5.5MHz
|
||||
#SPIDEV clock16 SPI4 DEVID5 MPU_EXT_CS MODE0 16*MHZ 16*MHZ # gives 10.6MHz
|
||||
|
||||
define HAL_CHIBIOS_ARCH_FMUV3 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
|
|
Loading…
Reference in New Issue