chibios_hwdef.py: add quiet option to remove parsing debug output

This commit is contained in:
Peter Barker 2023-05-25 11:27:45 +10:00 committed by Andrew Tridgell
parent 24f7ff7b61
commit ed1ae3b5f1
2 changed files with 33 additions and 23 deletions

View File

@ -25,12 +25,13 @@ class ChibiOSHWDef(object):
f1_vtypes = ['CRL', 'CRH', 'ODR'] f1_vtypes = ['CRL', 'CRH', 'ODR']
af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'SDMMC', 'OTG', 'JT', 'TIM', 'CAN', 'QUADSPI', 'OCTOSPI', 'ETH', 'MCO'] af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'SDMMC', 'OTG', 'JT', 'TIM', 'CAN', 'QUADSPI', 'OCTOSPI', 'ETH', 'MCO']
def __init__(self, bootloader=False, signed_fw=False, outdir=None, hwdef=[], default_params_filepath=None): def __init__(self, quiet=False, bootloader=False, signed_fw=False, outdir=None, hwdef=[], default_params_filepath=None):
self.outdir = outdir self.outdir = outdir
self.hwdef = hwdef self.hwdef = hwdef
self.bootloader = bootloader self.bootloader = bootloader
self.signed_fw = signed_fw self.signed_fw = signed_fw
self.default_params_filepath = default_params_filepath self.default_params_filepath = default_params_filepath
self.quiet = quiet
self.default_gpio = ['INPUT', 'FLOATING'] self.default_gpio = ['INPUT', 'FLOATING']
@ -771,7 +772,7 @@ class ChibiOSHWDef(object):
if ram_map is not None: if ram_map is not None:
return ram_map return ram_map
elif int(self.env_vars.get('USE_ALT_RAM_MAP', 0)) == 1: elif int(self.env_vars.get('USE_ALT_RAM_MAP', 0)) == 1:
print("Using ALT_RAM_MAP") self.progress("Using ALT_RAM_MAP")
return self.get_mcu_config('ALT_RAM_MAP', True) return self.get_mcu_config('ALT_RAM_MAP', True)
return self.get_mcu_config('RAM_MAP', True) return self.get_mcu_config('RAM_MAP', True)
@ -1037,7 +1038,6 @@ class ChibiOSHWDef(object):
if define == 'AP_NETWORKING_ENABLED' and value == 1: if define == 'AP_NETWORKING_ENABLED' and value == 1:
self.enable_networking(f) self.enable_networking(f)
if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1: if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1:
self.build_flags.append('USE_USB_MSD=yes') self.build_flags.append('USE_USB_MSD=yes')
@ -1163,7 +1163,7 @@ class ChibiOSHWDef(object):
cortex = self.get_mcu_config('CORTEX') cortex = self.get_mcu_config('CORTEX')
self.env_vars['CPU_FLAGS'] = self.get_mcu_config('CPU_FLAGS').split() self.env_vars['CPU_FLAGS'] = self.get_mcu_config('CPU_FLAGS').split()
build_info['MCU'] = cortex build_info['MCU'] = cortex
print("MCU Flags: %s %s" % (cortex, self.env_vars['CPU_FLAGS'])) self.progress("MCU Flags: %s %s" % (cortex, self.env_vars['CPU_FLAGS']))
elif self.mcu_series.startswith("STM32F1"): elif self.mcu_series.startswith("STM32F1"):
cortex = "cortex-m3" cortex = "cortex-m3"
self.env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex] self.env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex]
@ -1381,7 +1381,7 @@ class ChibiOSHWDef(object):
self.env_vars['FLASH_TOTAL'] = flash_length * 1024 self.env_vars['FLASH_TOTAL'] = flash_length * 1024
print("Generating ldscript.ld") self.progress("Generating ldscript.ld")
f = open(fname, 'w') f = open(fname, 'w')
ram0_start = ram_map[0][0] ram0_start = ram_map[0][0]
ram0_len = ram_map[0][1] * 1024 ram0_len = ram_map[0][1] * 1024
@ -1555,7 +1555,7 @@ INCLUDE common.ld
devlist = [] devlist = []
for dev in self.wspidev: for dev in self.wspidev:
if len(dev) != 6: if len(dev) != 6:
print("Badly formed WSPIDEV line %s" % dev) self.progress("Badly formed WSPIDEV line %s" % dev)
name = '"' + dev[0] + '"' name = '"' + dev[0] + '"'
bus = dev[1] bus = dev[1]
mode = dev[2] mode = dev[2]
@ -1596,7 +1596,7 @@ INCLUDE common.ld
return return
for t in list(self.bytype.keys()) + list(self.alttype.keys()): for t in list(self.bytype.keys()) + list(self.alttype.keys()):
print(t) self.progress(t)
if t.startswith('QUADSPI') or t.startswith('OCTOSPI'): if t.startswith('QUADSPI') or t.startswith('OCTOSPI'):
self.wspi_list.append(t) self.wspi_list.append(t)
@ -1999,7 +1999,7 @@ INCLUDE common.ld
def write_I2C_config(self, f): def write_I2C_config(self, f):
'''write I2C config defines''' '''write I2C config defines'''
if not self.have_type_prefix('I2C'): if not self.have_type_prefix('I2C'):
print("No I2C peripherals") self.progress("No I2C peripherals")
f.write(''' f.write('''
#ifndef HAL_USE_I2C #ifndef HAL_USE_I2C
#define HAL_USE_I2C FALSE #define HAL_USE_I2C FALSE
@ -2076,7 +2076,7 @@ INCLUDE common.ld
f.write('#define HAL_PWM_COUNT %u\n' % len(pwm_out)) f.write('#define HAL_PWM_COUNT %u\n' % len(pwm_out))
if not pwm_out and not alarm: if not pwm_out and not alarm:
print("No PWM output defined") self.progress("No PWM output defined")
f.write(''' f.write('''
#ifndef HAL_USE_PWM #ifndef HAL_USE_PWM
#define HAL_USE_PWM FALSE #define HAL_USE_PWM FALSE
@ -2527,7 +2527,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
def write_hwdef_header(self, outfilename): def write_hwdef_header(self, outfilename):
'''write hwdef header file''' '''write hwdef header file'''
print("Writing hwdef setup in %s" % outfilename) self.progress("Writing hwdef setup in %s" % outfilename)
tmpfile = outfilename + ".tmp" tmpfile = outfilename + ".tmp"
f = open(tmpfile, 'w') f = open(tmpfile, 'w')
@ -2600,7 +2600,8 @@ Please run: Tools/scripts/build_bootloaders.py %s
self.mcu_type, self.mcu_type,
dma_exclude=self.get_dma_exclude(self.periph_list), dma_exclude=self.get_dma_exclude(self.periph_list),
dma_priority=self.get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True), dma_priority=self.get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True),
dma_noshare=self.dma_noshare dma_noshare=self.dma_noshare,
quiet=self.quiet,
) )
if not self.is_bootloader_fw(): if not self.is_bootloader_fw():
@ -2720,7 +2721,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
# see if we ended up with the same file, on an unnecessary reconfigure # see if we ended up with the same file, on an unnecessary reconfigure
try: try:
if filecmp.cmp(outfilename, tmpfile): if filecmp.cmp(outfilename, tmpfile):
print("No change in hwdef.h") self.progress("No change in hwdef.h")
os.unlink(tmpfile) os.unlink(tmpfile)
return return
except Exception: except Exception:
@ -2824,13 +2825,13 @@ Please run: Tools/scripts/build_bootloaders.py %s
defaults_abspath = None defaults_abspath = None
if os.path.exists(defaults_path): if os.path.exists(defaults_path):
defaults_abspath = os.path.abspath(self.default_params_filepath) defaults_abspath = os.path.abspath(self.default_params_filepath)
print("Default parameters path from command line: %s" % self.default_params_filepath) self.progress("Default parameters path from command line: %s" % self.default_params_filepath)
elif os.path.exists(defaults_filename): elif os.path.exists(defaults_filename):
defaults_abspath = os.path.abspath(defaults_filename) defaults_abspath = os.path.abspath(defaults_filename)
print("Default parameters path from hwdef: %s" % defaults_filename) self.progress("Default parameters path from hwdef: %s" % defaults_filename)
if defaults_abspath is None: if defaults_abspath is None:
print("No default parameter file found") self.progress("No default parameter file found")
return return
content = self.get_processed_defaults_file(defaults_abspath) content = self.get_processed_defaults_file(defaults_abspath)
@ -3002,7 +3003,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
self.romfs_wildcard(a[1]) self.romfs_wildcard(a[1])
elif a[0] == 'undef': elif a[0] == 'undef':
for u in a[1:]: for u in a[1:]:
print("Removing %s" % u) self.progress("Removing %s" % u)
self.config.pop(u, '') self.config.pop(u, '')
self.bytype.pop(u, '') self.bytype.pop(u, '')
self.bylabel.pop(u, '') self.bylabel.pop(u, '')
@ -3034,7 +3035,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
if u == 'AIRSPEED': if u == 'AIRSPEED':
self.airspeed_list = [] self.airspeed_list = []
elif a[0] == 'env': elif a[0] == 'env':
print("Adding environment %s" % ' '.join(a[1:])) self.progress("Adding environment %s" % ' '.join(a[1:]))
if len(a[1:]) < 2: if len(a[1:]) < 2:
self.error("Bad env line for %s" % a[0]) self.error("Bad env line for %s" % a[0])
name = a[1] name = a[1]
@ -3045,6 +3046,11 @@ Please run: Tools/scripts/build_bootloaders.py %s
value = int(value, 0) value = int(value, 0)
self.env_vars[name] = value self.env_vars[name] = value
def progress(self, message):
if self.quiet:
return
print(message)
def process_file(self, filename): def process_file(self, filename):
'''process a hwdef.dat file''' '''process a hwdef.dat file'''
try: try:
@ -3063,7 +3069,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
dir = os.path.dirname(filename) dir = os.path.dirname(filename)
include_file = os.path.normpath( include_file = os.path.normpath(
os.path.join(dir, include_file)) os.path.join(dir, include_file))
print("Including %s" % include_file) self.progress("Including %s" % include_file)
self.process_file(include_file) self.process_file(include_file)
else: else:
self.process_line(line) self.process_line(line)
@ -3087,7 +3093,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
self.add_firmware_defaults_from_file(f, "defaults_bootloader.h", "bootloader") self.add_firmware_defaults_from_file(f, "defaults_bootloader.h", "bootloader")
def add_firmware_defaults_from_file(self, f, filename, description): def add_firmware_defaults_from_file(self, f, filename, description):
print("Setting up as %s" % description) self.progress("Setting up as %s" % description)
dirpath = os.path.dirname(os.path.realpath(__file__)) dirpath = os.path.dirname(os.path.realpath(__file__))
filepath = os.path.join(dirpath, filename) filepath = os.path.join(dirpath, filename)
@ -3144,7 +3150,7 @@ Please run: Tools/scripts/build_bootloaders.py %s
self.error("Missing MCU type in config") self.error("Missing MCU type in config")
self.mcu_type = self.get_config('MCU', 1) self.mcu_type = self.get_config('MCU', 1)
print("Setup for MCU %s" % self.mcu_type) self.progress("Setup for MCU %s" % self.mcu_type)
# build a list for peripherals for DMA resolver # build a list for peripherals for DMA resolver
self.periph_list = self.build_peripheral_list() self.periph_list = self.build_peripheral_list()
@ -3186,6 +3192,8 @@ if __name__ == '__main__':
'hwdef', type=str, nargs='+', default=None, help='hardware definition file') 'hwdef', type=str, nargs='+', default=None, help='hardware definition file')
parser.add_argument( parser.add_argument(
'--params', type=str, default=None, help='user default params path') '--params', type=str, default=None, help='user default params path')
parser.add_argument(
'--quiet', action='store_true', default=False, help='quiet running')
args = parser.parse_args() args = parser.parse_args()
@ -3194,6 +3202,7 @@ if __name__ == '__main__':
bootloader=args.bootloader, bootloader=args.bootloader,
signed_fw=args.signed_fw, signed_fw=args.signed_fw,
hwdef=args.hwdef, hwdef=args.hwdef,
default_params_filepath=args.params default_params_filepath=args.params,
quiet=args.quiet,
) )
c.run() c.run()

View File

@ -293,7 +293,7 @@ def forbidden_list(p, peripheral_list):
def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
dma_priority='', dma_noshare=[]): dma_priority='', dma_noshare=[], quiet=False):
'''write out a DMA resolver header file''' '''write out a DMA resolver header file'''
global dma_map, have_DMAMUX, has_bdshot global dma_map, have_DMAMUX, has_bdshot
timer_ch_periph = [] timer_ch_periph = []
@ -331,7 +331,8 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
dma_map = generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude, stream_ofs) dma_map = generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude, stream_ofs)
print("Writing DMA map") if not quiet:
print("Writing DMA map")
unassigned = [] unassigned = []
curr_dict = {} curr_dict = {}