dma_parse.py 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. #!/usr/bin/env python
  2. '''
  3. extra DMA mapping tables from a stm32 datasheet
  4. This assumes a csv file extracted from the datasheet using tablula:
  5. https://github.com/tabulapdf/tabula
  6. '''
  7. import sys, csv, os
  8. def parse_dma_table(fname, table):
  9. dma_num = 1
  10. csvt = csv.reader(open(fname,'rb'))
  11. i = 0
  12. last_channel = -1
  13. for row in csvt:
  14. if len(row) > 1 and row[1].startswith('Channel '):
  15. row = row[1:]
  16. if not row[0].startswith('Channel '):
  17. continue
  18. channel = int(row[0].split(' ')[1])
  19. if channel < last_channel:
  20. dma_num += 1
  21. last_channel = channel
  22. for stream in range(8):
  23. s = row[stream+1]
  24. s = s.replace('_\r', '_')
  25. s = s.replace('\r_', '_')
  26. if s == '-':
  27. continue
  28. keys = s.split()
  29. for k in keys:
  30. brace = k.find('(')
  31. if brace != -1:
  32. k = k[:brace]
  33. if k not in table:
  34. table[k] = []
  35. table[k] += [(dma_num, stream, channel)]
  36. def error(str):
  37. '''show an error and exit'''
  38. print("Error: " + str)
  39. sys.exit(1)
  40. def check_full_table(table):
  41. '''check the table is not missing rows or columns
  42. we should have at least one entry in every row and one entry in every colum of each dma table
  43. '''
  44. stream_mask = [0,0]
  45. channel_mask = [0,0]
  46. for k in table:
  47. for v in table[k]:
  48. (engine,stream,channel) = v
  49. if engine > 2 or engine < 1:
  50. error("Bad entry for %s: %s" % (k, v))
  51. stream_mask[engine-1] |= 1<<stream
  52. channel_mask[engine-1] |= 1<<channel
  53. for i in range(2):
  54. for c in range(8):
  55. if not ((1<<c) & channel_mask[i]):
  56. error("Missing channel %u for dma table %u" % (c, i))
  57. if not ((1<<c) & stream_mask[i]):
  58. error("Missing stream %u for dma table %u" % (c, i))
  59. table = {}
  60. if len(sys.argv) != 2:
  61. print("Error: expected a CSV files and output file")
  62. sys.exit(1)
  63. parse_dma_table(sys.argv[1], table)
  64. check_full_table(table)
  65. sys.stdout.write("DMA_Map = {\n");
  66. sys.stdout.write('\t# format is (DMA_TABLE, StreamNum, Channel)\n')
  67. sys.stdout.write('\t# extracted from %s\n' % os.path.basename(sys.argv[1]))
  68. for k in sorted(table.iterkeys()):
  69. s = '"%s"' % k
  70. sys.stdout.write('\t%-10s\t:\t[' % s)
  71. for i in range(len(table[k])):
  72. sys.stdout.write("(%u,%u,%u)" % (table[k][i][0], table[k][i][1], table[k][i][2]))
  73. if i < len(table[k])-1:
  74. sys.stdout.write(",")
  75. sys.stdout.write("],\n")
  76. sys.stdout.write("}\n");