mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: increase SPI clock for ICM42688 on CUAV-Nora
use regular speed for ICM42688 CS on Nora
This commit is contained in:
parent
68ec1c94f4
commit
52d3db487e
|
@ -70,7 +70,7 @@ PF2 RM3100_CS CS
|
|||
PG6 ICM20689_CS CS SPEED_VERYLOW
|
||||
PI12 ICM20649_CS CS SPEED_VERYLOW
|
||||
PE15 ICM20689_BOARD_CS CS SPEED_VERYLOW
|
||||
PA15 ICM42688_CS CS SPEED_VERYLOW
|
||||
PA15 ICM42688_CS CS
|
||||
PF3 BMI088_A_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
|
@ -240,7 +240,7 @@ SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
|||
SPIDEV icm20689_board SPI6 DEVID2 ICM20689_BOARD_CS MODE3 2*MHZ 8*MHZ
|
||||
|
||||
#Mount bmi088_a or icm42688 on SPI4
|
||||
SPIDEV icm42688 SPI4 DEVID2 ICM42688_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm42688 SPI4 DEVID2 ICM42688_CS MODE3 2*MHZ 16*MHZ
|
||||
|
||||
# two baro
|
||||
BARO MS56XX SPI:ms5611_imu
|
||||
|
@ -253,7 +253,7 @@ IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
|
|||
IMU Invensensev2 SPI:icm20649 ROTATION_NONE
|
||||
IMU Invensense SPI:icm20689_board ROTATION_NONE
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 7
|
||||
|
||||
# compasses
|
||||
|
||||
|
|
Loading…
Reference in New Issue