From 194f555c7b28c2a4cc269da340ed61a975d0aa2c Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 22 Mar 2023 08:29:45 +0000 Subject: [PATCH] AP_HAL_ChibiOS: provide mcu defaults in betaflight conversion --- .../hwdef/scripts/convert_betaflight_unified.py | 11 +++++++++++ 1 file changed, 11 insertions(+) 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 53d3602d27..0a36065750 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -45,6 +45,7 @@ alignment = { "CW90FLIP" : "ROTATION_ROLL_180", "CW180FLIP" : "ROTATION_ROLL_180_YAW_90", "CW270FLIP" : "ROTATION_PITCH_180", + "DEFAULT" : "ROTATION_NONE", } parser = argparse.ArgumentParser("convert_betaflight_unified.py") @@ -156,6 +157,11 @@ def convert_file(fname, board_id): reserve_start = 96 elif mcuclass == "H7": reserve_start = 384 + else: + mcuclass = "F4" + mcu = "F405" + flash_size = 1024 + reserve_start = 48 # preamble @@ -454,6 +460,11 @@ def convert_bootloader(fname, board_id): reserve_start = 96 elif mcuclass == "H7": reserve_start = 384 + else: + mcuclass = "F4" + mcu = "F405" + flash_size = 1024 + reserve_start = 48 # preamble