mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
HAL_ChibiOS: generate channel numbers in DMA tables
This commit is contained in:
parent
3501763f4e
commit
da2e79130b
@ -36,7 +36,33 @@ def parse_dma_table(fname, table):
|
||||
k = k[:brace]
|
||||
if k not in table:
|
||||
table[k] = []
|
||||
table[k] += [(dma_num, stream)]
|
||||
table[k] += [(dma_num, stream, channel)]
|
||||
|
||||
def error(str):
|
||||
'''show an error and exit'''
|
||||
print("Error: " + str)
|
||||
sys.exit(1)
|
||||
|
||||
def check_full_table(table):
|
||||
'''check the table is not missing rows or columns
|
||||
we should have at least one entry in every row and one entry in every colum of each dma table
|
||||
'''
|
||||
stream_mask = [0,0]
|
||||
channel_mask = [0,0]
|
||||
for k in table:
|
||||
for v in table[k]:
|
||||
(engine,stream,channel) = v
|
||||
if engine > 2 or engine < 1:
|
||||
error("Bad entry for %s: %s" % (k, v))
|
||||
stream_mask[engine-1] |= 1<<stream
|
||||
channel_mask[engine-1] |= 1<<channel
|
||||
for i in range(2):
|
||||
for c in range(8):
|
||||
if not ((1<<c) & channel_mask[i]):
|
||||
error("Missing channel %u for dma table %u" % (c, i))
|
||||
if not ((1<<c) & stream_mask[i]):
|
||||
error("Missing stream %u for dma table %u" % (c, i))
|
||||
|
||||
|
||||
table = {}
|
||||
|
||||
@ -46,15 +72,17 @@ if len(sys.argv) != 2:
|
||||
|
||||
parse_dma_table(sys.argv[1], table)
|
||||
|
||||
check_full_table(table)
|
||||
|
||||
sys.stdout.write("DMA_Map = {\n");
|
||||
sys.stdout.write('\t# format is [DMA_TABLE, StreamNum]\n')
|
||||
sys.stdout.write('\t# extracted from %sn\n' % os.path.basename(sys.argv[1]))
|
||||
sys.stdout.write('\t# format is (DMA_TABLE, StreamNum, Channel)\n')
|
||||
sys.stdout.write('\t# extracted from %s\n' % os.path.basename(sys.argv[1]))
|
||||
|
||||
for k in sorted(table.iterkeys()):
|
||||
s = '"%s"' % k
|
||||
sys.stdout.write('\t%-10s\t:\t[' % s)
|
||||
for i in range(len(table[k])):
|
||||
sys.stdout.write("(%u,%u)" % (table[k][i][0], table[k][i][1]))
|
||||
sys.stdout.write("(%u,%u,%u)" % (table[k][i][0], table[k][i][1], table[k][i][2]))
|
||||
if i < len(table[k])-1:
|
||||
sys.stdout.write(",")
|
||||
sys.stdout.write("],\n")
|
||||
|
Loading…
Reference in New Issue
Block a user