AP_HAL_ChibiOS: cope with sensor alignment not being set in betaflight config

This commit is contained in:
Andy Piper 2023-01-15 21:00:12 +00:00 committed by Andrew Tridgell
parent 13e3556e18
commit f9276f76e7

View File

@ -91,7 +91,11 @@ def write_imu_config(f, n):
global dma_noshare
global dma_pri
bus = settings['gyro_' + n + '_spibus']
align = settings['gyro_' + n + '_sensor_align']
sensor_align = 'gyro_' + n + '_sensor_align'
if sensor_align in settings:
align = settings[sensor_align]
else:
align = 'CW0'
f.write('''
# IMU setup
SPIDEV imu%s SPI%s DEVID1 GYRO%s_CS MODE3 1*MHZ 8*MHZ