From f9276f76e7489e3a5cd9c3f7959c0e5cb9b2f1b3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 15 Jan 2023 21:00:12 +0000 Subject: [PATCH] AP_HAL_ChibiOS: cope with sensor alignment not being set in betaflight config --- .../hwdef/scripts/convert_betaflight_unified.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py index aa6f14aa4d..817cb41f47 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -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