|
|
|
@ -25,6 +25,27 @@ def is_pin(str):
@@ -25,6 +25,27 @@ def is_pin(str):
|
|
|
|
|
except ValueError: |
|
|
|
|
return False |
|
|
|
|
|
|
|
|
|
def pin_compare(p1, p2): |
|
|
|
|
'''control pin sort order''' |
|
|
|
|
(p1,f1) = p1.split(':') |
|
|
|
|
(p2,f2) = p2.split(':') |
|
|
|
|
port1 = p1[:2] |
|
|
|
|
port2 = p2[:2] |
|
|
|
|
pin1 = int(p1[2:]) |
|
|
|
|
pin2 = int(p2[2:]) |
|
|
|
|
#print(port1, pin1, port2, pin2) |
|
|
|
|
if port1 == port2: |
|
|
|
|
if pin1 == pin2: |
|
|
|
|
if f1 < f2: |
|
|
|
|
return -1 |
|
|
|
|
return 1 |
|
|
|
|
if pin1 < pin2: |
|
|
|
|
return -1 |
|
|
|
|
return 1 |
|
|
|
|
if port1 < port2: |
|
|
|
|
return -1 |
|
|
|
|
return 1 |
|
|
|
|
|
|
|
|
|
def parse_af_table(fname, table): |
|
|
|
|
csvt = csv.reader(open(fname,'rb')) |
|
|
|
|
i = 0 |
|
|
|
@ -37,7 +58,9 @@ def parse_af_table(fname, table):
@@ -37,7 +58,9 @@ def parse_af_table(fname, table):
|
|
|
|
|
if s: |
|
|
|
|
aflist.append(int(s[2:])) |
|
|
|
|
if not is_pin(row[0]): |
|
|
|
|
continue |
|
|
|
|
if len(row) < 2 or not is_pin(row[1]): |
|
|
|
|
continue |
|
|
|
|
row = row[1:] |
|
|
|
|
pin = row[0] |
|
|
|
|
for i in range(len(aflist)): |
|
|
|
|
af = aflist[i] |
|
|
|
@ -63,7 +86,7 @@ parse_af_table(sys.argv[1], table)
@@ -63,7 +86,7 @@ parse_af_table(sys.argv[1], table)
|
|
|
|
|
sys.stdout.write("AltFunction_map = {\n"); |
|
|
|
|
sys.stdout.write('\t# format is PIN:FUNCTION : AFNUM\n') |
|
|
|
|
sys.stdout.write('\t# extracted from %s\n' % os.path.basename(sys.argv[1])) |
|
|
|
|
for k in sorted(table.keys()): |
|
|
|
|
for k in sorted(table.keys(), cmp=pin_compare): |
|
|
|
|
s = '"' + k + '"' |
|
|
|
|
sys.stdout.write('\t%-20s\t:\t%s,\n' % (s, table[k])) |
|
|
|
|
sys.stdout.write("}\n"); |
|
|
|
|