mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed AP_FILESYSTEM_ROMFS_ENABLED for peripherals with defaults.parm
now that defaults are in ROMFS we must enable AP_FILESYSTEM_ROMFS_ENABLED
This commit is contained in:
parent
7bdb8d770d
commit
9543eecf23
|
@ -38,6 +38,7 @@ class ChibiOSHWDef(object):
|
|||
self.signed_fw = signed_fw
|
||||
self.default_params_filepath = default_params_filepath
|
||||
self.quiet = quiet
|
||||
self.have_defaults_file = False
|
||||
|
||||
# if true then parameters will be appended in special apj-tool
|
||||
# section at end of binary:
|
||||
|
@ -2644,6 +2645,13 @@ Please run: Tools/scripts/build_bootloaders.py %s
|
|||
self.write_board_validate_macro(f)
|
||||
self.write_check_firmware(f)
|
||||
|
||||
if self.have_defaults_file:
|
||||
f.write('''
|
||||
#ifndef AP_FILESYSTEM_ROMFS_ENABLED
|
||||
#define AP_FILESYSTEM_ROMFS_ENABLED 1
|
||||
#endif
|
||||
''')
|
||||
|
||||
self.write_peripheral_enable(f)
|
||||
|
||||
if os.path.exists(self.processed_defaults_filepath()):
|
||||
|
@ -3277,6 +3285,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
|
|||
return
|
||||
|
||||
self.romfs_add('defaults.parm', filepath)
|
||||
self.have_defaults_file = True
|
||||
|
||||
def process_hwdefs(self):
|
||||
for fname in self.hwdef:
|
||||
|
|
Loading…
Reference in New Issue