AP_HAL_ChibiOS: added --extra-hwdef option

This commit is contained in:
willpiper 2021-06-18 18:00:24 +01:00 committed by Andrew Tridgell
parent 245f9d21b3
commit fb4a4e609a
1 changed files with 25 additions and 22 deletions

View File

@ -22,6 +22,8 @@ parser.add_argument(
'hwdef', type=str, default=None, help='hardware definition file') 'hwdef', type=str, 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(
'--extra-hwdef', type=str, default=None, help='Extra hwdef.dat file for custom build.')
args = parser.parse_args() args = parser.parse_args()
@ -2203,28 +2205,29 @@ def process_line(line):
env_vars[a[1]] = ' '.join(a[2:]) env_vars[a[1]] = ' '.join(a[2:])
def process_file(filename): def process_file(fname,extra_hwdef):
'''process a hwdef.dat file''' '''process a hwdef.dat file'''
try: for filename in [fname,extra_hwdef]:
f = open(filename, "r") try:
except Exception: f = open(filename, "r")
error("Unable to open file %s" % filename) except Exception:
for line in f.readlines(): error("Unable to open file %s" % filename)
line = line.split('#')[0] # ensure we discard the comments for line in f.readlines():
line = line.strip() line = line.split('#')[0] # ensure we discard the comments
if len(line) == 0 or line[0] == '#': line = line.strip()
continue if len(line) == 0 or line[0] == '#':
a = shlex.split(line) continue
if a[0] == "include" and len(a) > 1: a = shlex.split(line)
include_file = a[1] if a[0] == "include" and len(a) > 1:
if include_file[0] != '/': include_file = a[1]
dir = os.path.dirname(filename) if include_file[0] != '/':
include_file = os.path.normpath( dir = os.path.dirname(filename)
os.path.join(dir, include_file)) include_file = os.path.normpath(
print("Including %s" % include_file) os.path.join(dir, include_file))
process_file(include_file) print("Including %s" % include_file)
else: process_file(include_file)
process_line(line) else:
process_line(line)
def add_apperiph_defaults(f): def add_apperiph_defaults(f):
'''add default defines for peripherals''' '''add default defines for peripherals'''
@ -2258,7 +2261,7 @@ def add_apperiph_defaults(f):
# process input file # process input file
process_file(args.hwdef) process_file(args.hwdef,args.extra_hwdef)
outdir = args.outdir outdir = args.outdir
if outdir is None: if outdir is None: