mirror of https://github.com/ArduPilot/ardupilot
waf: boards.py: use chibios_hwdef.py to get boards list
This commit is contained in:
parent
a669249416
commit
720c8719dc
|
@ -12,6 +12,10 @@ import json
|
||||||
_board_classes = {}
|
_board_classes = {}
|
||||||
_board = None
|
_board = None
|
||||||
|
|
||||||
|
# modify our search path:
|
||||||
|
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../libraries/AP_HAL_ChibiOS/hwdef/scripts'))
|
||||||
|
import chibios_hwdef
|
||||||
|
|
||||||
class BoardMeta(type):
|
class BoardMeta(type):
|
||||||
def __init__(cls, name, bases, dct):
|
def __init__(cls, name, bases, dct):
|
||||||
super(BoardMeta, cls).__init__(name, bases, dct)
|
super(BoardMeta, cls).__init__(name, bases, dct)
|
||||||
|
@ -603,19 +607,9 @@ def get_ap_periph_boards():
|
||||||
continue
|
continue
|
||||||
hwdef = os.path.join(dirname, d, 'hwdef.dat')
|
hwdef = os.path.join(dirname, d, 'hwdef.dat')
|
||||||
if os.path.exists(hwdef):
|
if os.path.exists(hwdef):
|
||||||
with open(hwdef, "r") as f:
|
ch = chibios_hwdef.ChibiOSHWDef(hwdef=[hwdef], quiet=True)
|
||||||
content = f.read()
|
if ch.is_periph_fw_unprocessed():
|
||||||
if 'AP_PERIPH' in content:
|
list_ap.append(d)
|
||||||
list_ap.append(d)
|
|
||||||
continue
|
|
||||||
# process any include lines:
|
|
||||||
for m in re.finditer(r"^include\s+([^\s]*)", content, re.MULTILINE):
|
|
||||||
include_path = os.path.join(os.path.dirname(hwdef), m.group(1))
|
|
||||||
with open(include_path, "r") as g:
|
|
||||||
content = g.read()
|
|
||||||
if 'AP_PERIPH' in content:
|
|
||||||
list_ap.append(d)
|
|
||||||
break
|
|
||||||
|
|
||||||
list_ap = list(set(list_ap))
|
list_ap = list(set(list_ap))
|
||||||
return list_ap
|
return list_ap
|
||||||
|
|
|
@ -128,6 +128,9 @@ class ChibiOSHWDef(object):
|
||||||
# list of shared up timers
|
# list of shared up timers
|
||||||
self.shared_up = []
|
self.shared_up = []
|
||||||
|
|
||||||
|
# boolean indicating whether we have read and processed self.hwdef
|
||||||
|
self.processed_hwdefs = False
|
||||||
|
|
||||||
def is_int(self, str):
|
def is_int(self, str):
|
||||||
'''check if a string is an integer'''
|
'''check if a string is an integer'''
|
||||||
try:
|
try:
|
||||||
|
@ -3155,7 +3158,35 @@ Please run: Tools/scripts/build_bootloaders.py %s
|
||||||
|
|
||||||
self.add_firmware_defaults_from_file(f, "defaults_iofirmware.h", "IOMCU Firmware")
|
self.add_firmware_defaults_from_file(f, "defaults_iofirmware.h", "IOMCU Firmware")
|
||||||
|
|
||||||
|
def is_periph_fw_unprocessed_file(self, hwdef):
|
||||||
|
'''helper/recursion function for is_periph_fw_unprocessed'''
|
||||||
|
with open(hwdef, "r") as f:
|
||||||
|
content = f.read()
|
||||||
|
if 'AP_PERIPH' in content:
|
||||||
|
return True
|
||||||
|
# process any include lines:
|
||||||
|
for m in re.finditer(r"^include\s+([^\s]*)", content, re.MULTILINE):
|
||||||
|
include_path = os.path.join(os.path.dirname(hwdef), m.group(1))
|
||||||
|
if self.is_periph_fw_unprocessed_file(include_path):
|
||||||
|
return True
|
||||||
|
|
||||||
|
def is_periph_fw_unprocessed(self):
|
||||||
|
'''it takes ~2 seconds to process all hwdefs. This is a shortcut to
|
||||||
|
make things much faster in the case we are filtering boards to
|
||||||
|
just peripherals. Note that this parsing is very coarse -
|
||||||
|
AP_PERIPH could be in a comment or part of a define
|
||||||
|
(e.g. AP_PERIPH_GPS_SUPPORT), for example, and this method
|
||||||
|
will still return True. Also can't "undef" AP_PERIPH - if we
|
||||||
|
ever see the string we return true.
|
||||||
|
'''
|
||||||
|
for hwdef in self.hwdef:
|
||||||
|
if self.is_periph_fw_unprocessed_file(hwdef):
|
||||||
|
return True
|
||||||
|
return False
|
||||||
|
|
||||||
def is_periph_fw(self):
|
def is_periph_fw(self):
|
||||||
|
if not self.processed_hwdefs:
|
||||||
|
raise ValueError("Need to process_hwdefs() first")
|
||||||
return int(self.env_vars.get('AP_PERIPH', 0)) != 0
|
return int(self.env_vars.get('AP_PERIPH', 0)) != 0
|
||||||
|
|
||||||
def is_normal_fw(self):
|
def is_normal_fw(self):
|
||||||
|
@ -3202,11 +3233,14 @@ Please run: Tools/scripts/build_bootloaders.py %s
|
||||||
|
|
||||||
self.romfs_add('defaults.parm', filepath)
|
self.romfs_add('defaults.parm', filepath)
|
||||||
|
|
||||||
def run(self):
|
def process_hwdefs(self):
|
||||||
|
|
||||||
# process input file
|
|
||||||
for fname in self.hwdef:
|
for fname in self.hwdef:
|
||||||
self.process_file(fname)
|
self.process_file(fname)
|
||||||
|
self.processed_hwdefs = True
|
||||||
|
|
||||||
|
def run(self):
|
||||||
|
# process input file
|
||||||
|
self.process_hwdefs()
|
||||||
|
|
||||||
if "MCU" not in self.config:
|
if "MCU" not in self.config:
|
||||||
self.error("Missing MCU type in config")
|
self.error("Missing MCU type in config")
|
||||||
|
|
Loading…
Reference in New Issue