hwdef: fix IMU orientation

This commit is contained in:
rishabsingh3003 2025-01-01 00:46:29 -05:00
parent 6544fe80f7
commit cfe03532dd

View File

@ -148,7 +148,7 @@ SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
# SDCard
SPIDEV sdcard SPI3 DEVID1 SDCARD1_CS MODE0 400*KHZ 25*MHZ
IMU Invensensev3 SPI:imu1 ROTATION_NONE
IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_90
DMA_NOSHARE TIM3_UP TIM8_UP TIM2_UP SPI1*
DMA_PRIORITY TIM3_UP TIM8_UP TIM2_UP SPI1*
@ -158,7 +158,7 @@ define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 3
define HAL_DEFAULT_INS_FAST_SAMPLE 1
# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12