|
|
|
@ -1416,6 +1416,14 @@ def write_QSPI_config(f):
@@ -1416,6 +1416,14 @@ def write_QSPI_config(f):
|
|
|
|
|
f.write('#define HAL_QSPI_BUS_LIST %s\n\n' % ','.join(devlist)) |
|
|
|
|
write_QSPI_table(f) |
|
|
|
|
|
|
|
|
|
def write_check_firmware(f): |
|
|
|
|
'''add AP_CHECK_FIRMWARE_ENABLED if needed''' |
|
|
|
|
if env_vars.get('AP_PERIPH',0) != 0 or intdefines.get('AP_OPENDRONEID_ENABLED',0) == 1: |
|
|
|
|
f.write(''' |
|
|
|
|
#ifndef AP_CHECK_FIRMWARE_ENABLED |
|
|
|
|
#define AP_CHECK_FIRMWARE_ENABLED 1 |
|
|
|
|
#endif |
|
|
|
|
''') |
|
|
|
|
|
|
|
|
|
def parse_spi_device(dev): |
|
|
|
|
'''parse a SPI:xxx device item''' |
|
|
|
@ -2295,6 +2303,7 @@ def write_hwdef_header(outfilename):
@@ -2295,6 +2303,7 @@ def write_hwdef_header(outfilename):
|
|
|
|
|
write_AIRSPEED_config(f) |
|
|
|
|
write_board_validate_macro(f) |
|
|
|
|
add_apperiph_defaults(f) |
|
|
|
|
write_check_firmware(f) |
|
|
|
|
|
|
|
|
|
write_peripheral_enable(f) |
|
|
|
|
|
|
|
|
@ -2731,10 +2740,6 @@ def add_apperiph_defaults(f):
@@ -2731,10 +2740,6 @@ def add_apperiph_defaults(f):
|
|
|
|
|
# not AP_Periph |
|
|
|
|
return |
|
|
|
|
|
|
|
|
|
if not args.bootloader: |
|
|
|
|
# use the app descriptor needed by MissionPlanner for CAN upload |
|
|
|
|
env_vars['APP_DESCRIPTOR'] = 'MissionPlanner' |
|
|
|
|
|
|
|
|
|
print("Setting up as AP_Periph") |
|
|
|
|
f.write(''' |
|
|
|
|
#ifndef HAL_SCHEDULER_ENABLED |
|
|
|
|