@@ -128,6 +128,9 @@ def __init__(self, quiet=False, bootloader=False, signed_fw=False, outdir=None,
128
128
# list of shared up timers
129
129
self .shared_up = []
130
130
131
+ # boolean indicating whether we have read and processed self.hwdef
132
+ self .processed_hwdefs = False
133
+
131
134
def is_int (self , str ):
132
135
'''check if a string is an integer'''
133
136
try :
@@ -3131,7 +3134,35 @@ def add_iomcu_firmware_defaults(self, f):
3131
3134
3132
3135
self .add_firmware_defaults_from_file (f , "defaults_iofirmware.h" , "IOMCU Firmware" )
3133
3136
3137
+ def is_periph_fw_unprocessed_file (self , hwdef ):
3138
+ '''helper/recursion function for is_periph_fw_unprocessed'''
3139
+ with open (hwdef , "r" ) as f :
3140
+ content = f .read ()
3141
+ if 'AP_PERIPH' in content :
3142
+ return True
3143
+ # process any include lines:
3144
+ for m in re .finditer (r"^include\s+([^\s]*)" , content , re .MULTILINE ):
3145
+ include_path = os .path .join (os .path .dirname (hwdef ), m .group (1 ))
3146
+ if self .is_periph_fw_unprocessed_file (include_path ):
3147
+ return True
3148
+
3149
+ def is_periph_fw_unprocessed (self ):
3150
+ '''it takes ~2 seconds to process all hwdefs. This is a shortcut to
3151
+ make things much faster in the cvase we are filtering boads to
3152
+ just peripherals. Note that this parsing is very coarse -
3153
+ AP_PERIPH could be in a comment or part of a define
3154
+ (e.g. AP_PERIPH_GPS_SUPPORT), for example, and this method
3155
+ will still return True. Also can't "undef" AP_PERIPH - if we
3156
+ ever see the string we return true.
3157
+ '''
3158
+ for hwdef in self .hwdef :
3159
+ if self .is_periph_fw_unprocessed_file (hwdef ):
3160
+ return True
3161
+ return False
3162
+
3134
3163
def is_periph_fw (self ):
3164
+ if not self .processed_hwdefs :
3165
+ raise ValueError ("Need to process_hwdefs() first" )
3135
3166
return int (self .env_vars .get ('AP_PERIPH' , 0 )) != 0
3136
3167
3137
3168
def is_normal_fw (self ):
@@ -3178,11 +3209,14 @@ def write_default_parameters(self):
3178
3209
3179
3210
self .romfs_add ('defaults.parm' , filepath )
3180
3211
3181
- def run (self ):
3182
-
3183
- # process input file
3212
+ def process_hwdefs (self ):
3184
3213
for fname in self .hwdef :
3185
3214
self .process_file (fname )
3215
+ self .processed_hwdefs = True
3216
+
3217
+ def run (self ):
3218
+ # process input file
3219
+ self .process_hwdefs ()
3186
3220
3187
3221
if "MCU" not in self .config :
3188
3222
self .error ("Missing MCU type in config" )
0 commit comments