mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_ChibiOS: cope with sensor alignment not being set in betaflight config
This commit is contained in:
parent
13e3556e18
commit
f9276f76e7
@ -91,7 +91,11 @@ def write_imu_config(f, n):
|
|||||||
global dma_noshare
|
global dma_noshare
|
||||||
global dma_pri
|
global dma_pri
|
||||||
bus = settings['gyro_' + n + '_spibus']
|
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('''
|
f.write('''
|
||||||
# IMU setup
|
# IMU setup
|
||||||
SPIDEV imu%s SPI%s DEVID1 GYRO%s_CS MODE3 1*MHZ 8*MHZ
|
SPIDEV imu%s SPI%s DEVID1 GYRO%s_CS MODE3 1*MHZ 8*MHZ
|
||||||
|
Loading…
Reference in New Issue
Block a user