AP_HAL_ChibiOS: provide mcu defaults in betaflight conversion

This commit is contained in:
Andy Piper 2023-03-22 08:29:45 +00:00 committed by Randy Mackay
parent 4e1b1845fe
commit 78cbdc62fa
1 changed files with 11 additions and 0 deletions

View File

@ -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
@ -456,6 +462,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