mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_ChibiOS: drop mRoControlZeroF7 DPS310 clock to 5MHz
This commit is contained in:
parent
94418ca70e
commit
97dc76732c
@ -225,7 +225,7 @@ PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||
# names used in AnalogIn.cpp.
|
||||
PB5 VDD_BRICK_VALID INPUT PULLUP
|
||||
|
||||
SPIDEV dps280 SPI2 DEVID3 BARO_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
|
||||
SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 8*MHZ
|
||||
@ -280,7 +280,7 @@ IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE
|
||||
|
||||
# 1 baro
|
||||
BARO DPS280 SPI:dps280
|
||||
BARO DPS280 SPI:dps310
|
||||
|
||||
# 1 compass
|
||||
COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180
|
||||
|
Loading…
Reference in New Issue
Block a user