mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
AP_HAL_ChibiOS: addressed reviewed comments
This commit is contained in:
parent
15cd9d502d
commit
ce1ee6334f
@ -2205,29 +2205,28 @@ def process_line(line):
|
|||||||
env_vars[a[1]] = ' '.join(a[2:])
|
env_vars[a[1]] = ' '.join(a[2:])
|
||||||
|
|
||||||
|
|
||||||
def process_file(fname,extra_hwdef):
|
def process_file(filename):
|
||||||
'''process a hwdef.dat file'''
|
'''process a hwdef.dat file'''
|
||||||
for filename in [fname,extra_hwdef]:
|
try:
|
||||||
try:
|
f = open(filename, "r")
|
||||||
f = open(filename, "r")
|
except Exception:
|
||||||
except Exception:
|
error("Unable to open file %s" % filename)
|
||||||
error("Unable to open file %s" % filename)
|
for line in f.readlines():
|
||||||
for line in f.readlines():
|
line = line.split('#')[0] # ensure we discard the comments
|
||||||
line = line.split('#')[0] # ensure we discard the comments
|
line = line.strip()
|
||||||
line = line.strip()
|
if len(line) == 0 or line[0] == '#':
|
||||||
if len(line) == 0 or line[0] == '#':
|
continue
|
||||||
continue
|
a = shlex.split(line)
|
||||||
a = shlex.split(line)
|
if a[0] == "include" and len(a) > 1:
|
||||||
if a[0] == "include" and len(a) > 1:
|
include_file = a[1]
|
||||||
include_file = a[1]
|
if include_file[0] != '/':
|
||||||
if include_file[0] != '/':
|
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)
|
||||||
print("Including %s" % include_file)
|
process_file(include_file)
|
||||||
process_file(include_file)
|
else:
|
||||||
else:
|
process_line(line)
|
||||||
process_line(line)
|
|
||||||
|
|
||||||
def add_apperiph_defaults(f):
|
def add_apperiph_defaults(f):
|
||||||
'''add default defines for peripherals'''
|
'''add default defines for peripherals'''
|
||||||
@ -2261,7 +2260,11 @@ def add_apperiph_defaults(f):
|
|||||||
|
|
||||||
|
|
||||||
# process input file
|
# process input file
|
||||||
process_file(args.hwdef,args.extra_hwdef)
|
if args.hwdef != None:
|
||||||
|
for filename in [args.hwdef,args.extra_hwdef]:
|
||||||
|
process_file(filename)
|
||||||
|
else:
|
||||||
|
process_file(args.hwdef)
|
||||||
|
|
||||||
outdir = args.outdir
|
outdir = args.outdir
|
||||||
if outdir is None:
|
if outdir is None:
|
||||||
|
Loading…
Reference in New Issue
Block a user