mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: CubeRedSecondary IMU orientation fix
Also remove duplicate RC_IN serial protocol
This commit is contained in:
parent
a654962b4c
commit
9b981cc7f3
@ -64,7 +64,7 @@ SPIDEV icm42688 SPI2 DEVID1 ICM_CS MODE3 2*MHZ 8*MHZ
|
|||||||
SPIDEV ms5611 SPI4 DEVID2 BARO_CS MODE3 20*MHZ 20*MHZ
|
SPIDEV ms5611 SPI4 DEVID2 BARO_CS MODE3 20*MHZ 20*MHZ
|
||||||
|
|
||||||
BARO MS56XX SPI:ms5611
|
BARO MS56XX SPI:ms5611
|
||||||
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
|
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180
|
||||||
|
|
||||||
CHECK_ICM42688 spi_check_register("icm42688", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688)
|
CHECK_ICM42688 spi_check_register("icm42688", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688)
|
||||||
CHECK_ICM45686 spi_check_register("icm42688", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)
|
CHECK_ICM45686 spi_check_register("icm42688", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)
|
||||||
@ -148,7 +148,6 @@ SERIAL_ORDER UART7 UART8 USART3 USART6 UART4 USART2
|
|||||||
|
|
||||||
# use 2 MBaud when talking to primary controller
|
# use 2 MBaud when talking to primary controller
|
||||||
define DEFAULT_SERIAL0_BAUD 2000000
|
define DEFAULT_SERIAL0_BAUD 2000000
|
||||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
|
||||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1
|
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1
|
||||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user