chibios_hwdef.py 57 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721
  1. #!/usr/bin/env python
  2. '''
  3. setup board.h for chibios
  4. '''
  5. import argparse, sys, fnmatch, os, dma_resolver, shlex, pickle, re
  6. import shutil
  7. parser = argparse.ArgumentParser("chibios_pins.py")
  8. parser.add_argument(
  9. '-D', '--outdir', type=str, default=None, help='Output directory')
  10. parser.add_argument(
  11. '--bootloader', action='store_true', default=False, help='configure for bootloader')
  12. parser.add_argument(
  13. 'hwdef', type=str, default=None, help='hardware definition file')
  14. args = parser.parse_args()
  15. # output variables for each pin
  16. f4f7_vtypes = ['MODER', 'OTYPER', 'OSPEEDR', 'PUPDR', 'ODR', 'AFRL', 'AFRH']
  17. f1_vtypes = ['CRL', 'CRH', 'ODR']
  18. f1_input_sigs = ['RX', 'MISO', 'CTS']
  19. f1_output_sigs = ['TX', 'MOSI', 'SCK', 'RTS', 'CH1', 'CH2', 'CH3', 'CH4']
  20. af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'SDMMC', 'OTG', 'JT', 'TIM', 'CAN']
  21. vtypes = []
  22. # number of pins in each port
  23. pincount = {
  24. 'A': 16,
  25. 'B': 16,
  26. 'C': 16,
  27. 'D': 16,
  28. 'E': 16,
  29. 'F': 16,
  30. 'G': 16,
  31. 'H': 2,
  32. 'I': 0,
  33. 'J': 0,
  34. 'K': 0
  35. }
  36. ports = pincount.keys()
  37. portmap = {}
  38. # dictionary of all config lines, indexed by first word
  39. config = {}
  40. # list of all pins in config file order
  41. allpins = []
  42. # list of configs by type
  43. bytype = {}
  44. # list of configs by label
  45. bylabel = {}
  46. # list of SPI devices
  47. spidev = []
  48. # dictionary of ROMFS files
  49. romfs = {}
  50. # SPI bus list
  51. spi_list = []
  52. # all config lines in order
  53. alllines = []
  54. # allow for extra env vars
  55. env_vars = {}
  56. # build flags for ChibiOS makefiles
  57. build_flags = []
  58. # sensor lists
  59. imu_list = []
  60. compass_list = []
  61. baro_list = []
  62. mcu_type = None
  63. def is_int(str):
  64. '''check if a string is an integer'''
  65. try:
  66. int(str)
  67. except Exception:
  68. return False
  69. return True
  70. def error(str):
  71. '''show an error and exit'''
  72. print("Error: " + str)
  73. sys.exit(1)
  74. def get_mcu_lib(mcu):
  75. '''get library file for the chosen MCU'''
  76. import importlib
  77. try:
  78. return importlib.import_module(mcu)
  79. except ImportError:
  80. error("Unable to find module for MCU %s" % mcu)
  81. def setup_mcu_type_defaults():
  82. '''setup defaults for given mcu type'''
  83. global pincount, ports, portmap, vtypes
  84. lib = get_mcu_lib(mcu_type)
  85. if hasattr(lib, 'pincount'):
  86. pincount = lib.pincount
  87. if mcu_series.startswith("STM32F1"):
  88. vtypes = f1_vtypes
  89. else:
  90. vtypes = f4f7_vtypes
  91. ports = pincount.keys()
  92. # setup default as input pins
  93. for port in ports:
  94. portmap[port] = []
  95. for pin in range(pincount[port]):
  96. portmap[port].append(generic_pin(port, pin, None, 'INPUT', []))
  97. def get_alt_function(mcu, pin, function):
  98. '''return alternative function number for a pin'''
  99. lib = get_mcu_lib(mcu)
  100. if function.endswith('_TXINV') or function.endswith('_RXINV'):
  101. # RXINV and TXINV are special labels for inversion pins, not alt-functions
  102. return None
  103. if hasattr(lib, "AltFunction_map"):
  104. alt_map = lib.AltFunction_map
  105. else:
  106. # just check if Alt Func is available or not
  107. for l in af_labels:
  108. if function.startswith(l):
  109. return 0
  110. return None
  111. if function and function.endswith("_RTS") and (
  112. function.startswith('USART') or function.startswith('UART')):
  113. # we do software RTS
  114. return None
  115. for l in af_labels:
  116. if function.startswith(l):
  117. s = pin + ":" + function
  118. if not s in alt_map:
  119. error("Unknown pin function %s for MCU %s" % (s, mcu))
  120. return alt_map[s]
  121. return None
  122. def have_type_prefix(ptype):
  123. '''return True if we have a peripheral starting with the given peripheral type'''
  124. for t in bytype.keys():
  125. if t.startswith(ptype):
  126. return True
  127. return False
  128. def get_ADC1_chan(mcu, pin):
  129. '''return ADC1 channel for an analog pin'''
  130. import importlib
  131. try:
  132. lib = importlib.import_module(mcu)
  133. ADC1_map = lib.ADC1_map
  134. except ImportError:
  135. error("Unable to find ADC1_Map for MCU %s" % mcu)
  136. if not pin in ADC1_map:
  137. error("Unable to find ADC1 channel for pin %s" % pin)
  138. return ADC1_map[pin]
  139. class generic_pin(object):
  140. '''class to hold pin definition'''
  141. def __init__(self, port, pin, label, type, extra):
  142. global mcu_series
  143. self.portpin = "P%s%u" % (port, pin)
  144. self.port = port
  145. self.pin = pin
  146. self.label = label
  147. self.type = type
  148. self.extra = extra
  149. self.af = None
  150. if type == 'OUTPUT':
  151. self.sig_dir = 'OUTPUT'
  152. else:
  153. self.sig_dir = 'INPUT'
  154. if mcu_series.startswith("STM32F1") and self.label is not None:
  155. self.f1_pin_setup()
  156. # check that labels and pin types are consistent
  157. for prefix in ['USART', 'UART', 'TIM']:
  158. if label is None or type is None:
  159. continue
  160. if type.startswith(prefix):
  161. a1 = label.split('_')
  162. a2 = type.split('_')
  163. if a1[0] != a2[0]:
  164. error("Peripheral prefix mismatch for %s %s %s" % (self.portpin, label, type))
  165. def f1_pin_setup(self):
  166. for l in af_labels:
  167. if self.label.startswith(l):
  168. if self.label.endswith(tuple(f1_input_sigs)):
  169. self.sig_dir = 'INPUT'
  170. self.extra.append('FLOATING')
  171. elif self.label.endswith(tuple(f1_output_sigs)):
  172. self.sig_dir = 'OUTPUT'
  173. elif l == 'I2C':
  174. self.sig_dir = 'OUTPUT'
  175. else:
  176. error("Unknown signal type %s:%s for %s!" % (self.portpin, self.label, mcu_type))
  177. def has_extra(self, v):
  178. '''return true if we have the given extra token'''
  179. return v in self.extra
  180. def extra_prefix(self, prefix):
  181. '''find an extra token starting with the given prefix'''
  182. for e in self.extra:
  183. if e.startswith(prefix):
  184. return e
  185. return None
  186. def extra_value(self, name, type=None, default=None):
  187. '''find an extra value of given type'''
  188. v = self.extra_prefix(name)
  189. if v is None:
  190. return default
  191. if v[len(name)] != '(' or v[-1] != ')':
  192. error("Badly formed value for %s: %s\n" % (name, v))
  193. ret = v[len(name) + 1:-1]
  194. if type is not None:
  195. try:
  196. ret = type(ret)
  197. except Exception:
  198. error("Badly formed value for %s: %s\n" % (name, ret))
  199. return ret
  200. def is_RTS(self):
  201. '''return true if this is a RTS pin'''
  202. if self.label and self.label.endswith("_RTS") and (
  203. self.type.startswith('USART') or self.type.startswith('UART')):
  204. return True
  205. return False
  206. def is_CS(self):
  207. '''return true if this is a CS pin'''
  208. return self.has_extra("CS") or self.type == "CS"
  209. def get_MODER(self):
  210. '''return one of ALTERNATE, OUTPUT, ANALOG, INPUT'''
  211. if self.af is not None:
  212. v = "ALTERNATE"
  213. elif self.type == 'OUTPUT':
  214. v = "OUTPUT"
  215. elif self.type.startswith('ADC'):
  216. v = "ANALOG"
  217. elif self.is_CS():
  218. v = "OUTPUT"
  219. elif self.is_RTS():
  220. v = "OUTPUT"
  221. else:
  222. v = "INPUT"
  223. return "PIN_MODE_%s(%uU)" % (v, self.pin)
  224. def get_OTYPER(self):
  225. '''return one of PUSHPULL, OPENDRAIN'''
  226. v = 'PUSHPULL'
  227. if self.type.startswith('I2C'):
  228. # default I2C to OPENDRAIN
  229. v = 'OPENDRAIN'
  230. values = ['PUSHPULL', 'OPENDRAIN']
  231. for e in self.extra:
  232. if e in values:
  233. v = e
  234. return "PIN_OTYPE_%s(%uU)" % (v, self.pin)
  235. def get_OSPEEDR(self):
  236. '''return one of SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH'''
  237. # on STM32F4 these speeds correspond to 2MHz, 25MHz, 50MHz and 100MHz
  238. values = ['SPEED_VERYLOW', 'SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH']
  239. v = 'SPEED_MEDIUM'
  240. for e in self.extra:
  241. if e in values:
  242. v = e
  243. return "PIN_O%s(%uU)" % (v, self.pin)
  244. def get_PUPDR(self):
  245. '''return one of FLOATING, PULLUP, PULLDOWN'''
  246. values = ['FLOATING', 'PULLUP', 'PULLDOWN']
  247. v = 'FLOATING'
  248. if self.is_CS():
  249. v = "PULLUP"
  250. # generate pullups for UARTs
  251. if (self.type.startswith('USART') or
  252. self.type.startswith('UART')) and (
  253. (self.label.endswith('_TX') or
  254. self.label.endswith('_RX') or
  255. self.label.endswith('_CTS') or
  256. self.label.endswith('_RTS'))):
  257. v = "PULLUP"
  258. # generate pullups for SDIO and SDMMC
  259. if (self.type.startswith('SDIO') or
  260. self.type.startswith('SDMMC')) and (
  261. (self.label.endswith('_D0') or
  262. self.label.endswith('_D1') or
  263. self.label.endswith('_D2') or
  264. self.label.endswith('_D3') or
  265. self.label.endswith('_CMD'))):
  266. v = "PULLUP"
  267. for e in self.extra:
  268. if e in values:
  269. v = e
  270. return "PIN_PUPDR_%s(%uU)" % (v, self.pin)
  271. def get_ODR_F1(self):
  272. '''return one of LOW, HIGH'''
  273. values = ['LOW', 'HIGH']
  274. v = 'HIGH'
  275. if self.type == 'OUTPUT':
  276. v = 'LOW'
  277. for e in self.extra:
  278. if e in values:
  279. v = e
  280. #for some controllers input pull up down is selected by ODR
  281. if self.type == "INPUT":
  282. v = 'LOW'
  283. if 'PULLUP' in self.extra:
  284. v = "HIGH"
  285. return "PIN_ODR_%s(%uU)" % (v, self.pin)
  286. def get_ODR(self):
  287. '''return one of LOW, HIGH'''
  288. if mcu_series.startswith("STM32F1"):
  289. return self.get_ODR_F1()
  290. values = ['LOW', 'HIGH']
  291. v = 'HIGH'
  292. for e in self.extra:
  293. if e in values:
  294. v = e
  295. return "PIN_ODR_%s(%uU)" % (v, self.pin)
  296. def get_AFIO(self):
  297. '''return AFIO'''
  298. af = self.af
  299. if af is None:
  300. af = 0
  301. return "PIN_AFIO_AF(%uU, %uU)" % (self.pin, af)
  302. def get_AFRL(self):
  303. '''return AFIO low 8'''
  304. if self.pin >= 8:
  305. return None
  306. return self.get_AFIO()
  307. def get_AFRH(self):
  308. '''return AFIO high 8'''
  309. if self.pin < 8:
  310. return None
  311. return self.get_AFIO()
  312. def get_CR_F1(self):
  313. '''return CR FLAGS for STM32F1xx'''
  314. #Check Speed
  315. if self.sig_dir != "INPUT" or self.af is not None:
  316. speed_values = ['SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH']
  317. v = 'SPEED_MEDIUM'
  318. for e in self.extra:
  319. if e in speed_values:
  320. v = e
  321. speed_str = "PIN_%s(%uU) |" % (v, self.pin)
  322. else:
  323. speed_str = ""
  324. if self.af is not None:
  325. if self.label.endswith('_RX'):
  326. # uart RX is configured as a input, and can be pullup, pulldown or float
  327. if 'PULLUP' in self.extra or 'PULLDOWN' in self.extra:
  328. v = 'PUD'
  329. else:
  330. v = "NOPULL"
  331. else:
  332. v = "AF_PP"
  333. elif self.sig_dir == 'OUTPUT':
  334. if 'OPENDRAIN' in self.extra:
  335. v = 'OUTPUT_OD'
  336. else:
  337. v = "OUTPUT_PP"
  338. elif self.type.startswith('ADC'):
  339. v = "ANALOG"
  340. else:
  341. v = "PUD"
  342. if 'FLOATING' in self.extra:
  343. v = "NOPULL"
  344. mode_str = "PIN_MODE_%s(%uU)" % (v, self.pin)
  345. return "%s %s" % (speed_str, mode_str)
  346. def get_CR(self):
  347. '''return CR FLAGS'''
  348. if mcu_series.startswith("STM32F1"):
  349. return self.get_CR_F1()
  350. if self.sig_dir != "INPUT":
  351. speed_values = ['SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH']
  352. v = 'SPEED_MEDIUM'
  353. for e in self.extra:
  354. if e in speed_values:
  355. v = e
  356. speed_str = "PIN_%s(%uU) |" % (v, self.pin)
  357. else:
  358. speed_str = ""
  359. #Check Alternate function
  360. if self.type.startswith('I2C'):
  361. v = "AF_OD"
  362. elif self.sig_dir == 'OUTPUT':
  363. if self.af is not None:
  364. v = "AF_PP"
  365. else:
  366. v = "OUTPUT_PP"
  367. elif self.type.startswith('ADC'):
  368. v = "ANALOG"
  369. elif self.is_CS():
  370. v = "OUTPUT_PP"
  371. elif self.is_RTS():
  372. v = "OUTPUT_PP"
  373. else:
  374. v = "PUD"
  375. if 'FLOATING' in self.extra:
  376. v = "NOPULL"
  377. mode_str = "PIN_MODE_%s(%uU)" % (v, self.pin)
  378. return "%s %s" % (speed_str, mode_str)
  379. def get_CRH(self):
  380. if self.pin < 8:
  381. return None
  382. return self.get_CR()
  383. def get_CRL(self):
  384. if self.pin >= 8:
  385. return None
  386. return self.get_CR()
  387. def __str__(self):
  388. str = ''
  389. if self.af is not None:
  390. str += " AF%u" % self.af
  391. if self.type.startswith('ADC1'):
  392. str += " ADC1_IN%u" % get_ADC1_chan(mcu_type, self.portpin)
  393. if self.extra_value('PWM', type=int):
  394. str += " PWM%u" % self.extra_value('PWM', type=int)
  395. return "P%s%u %s %s%s" % (self.port, self.pin, self.label, self.type,
  396. str)
  397. def get_config(name, column=0, required=True, default=None, type=None, spaces=False):
  398. '''get a value from config dictionary'''
  399. if not name in config:
  400. if required and default is None:
  401. error("missing required value %s in hwdef.dat" % name)
  402. return default
  403. if len(config[name]) < column + 1:
  404. if not required:
  405. return None
  406. error("missing required value %s in hwdef.dat (column %u)" % (name,
  407. column))
  408. if spaces:
  409. ret = ' '.join(config[name][column:])
  410. else:
  411. ret = config[name][column]
  412. if type is not None:
  413. if type == int and ret.startswith('0x'):
  414. try:
  415. ret = int(ret,16)
  416. except Exception:
  417. error("Badly formed config value %s (got %s)" % (name, ret))
  418. else:
  419. try:
  420. ret = type(ret)
  421. except Exception:
  422. error("Badly formed config value %s (got %s)" % (name, ret))
  423. return ret
  424. def get_mcu_config(name, required=False):
  425. '''get a value from the mcu dictionary'''
  426. lib = get_mcu_lib(mcu_type)
  427. if not hasattr(lib, 'mcu'):
  428. error("Missing mcu config for %s" % mcu_type)
  429. if not name in lib.mcu:
  430. if required:
  431. error("Missing required mcu config %s for %s" % (name, mcu_type))
  432. return None
  433. return lib.mcu[name]
  434. def enable_can(f):
  435. '''setup for a CAN enabled board'''
  436. f.write('#define HAL_WITH_UAVCAN 1\n')
  437. env_vars['HAL_WITH_UAVCAN'] = '1'
  438. def has_sdcard_spi():
  439. '''check for sdcard connected to spi bus'''
  440. for dev in spidev:
  441. if(dev[0] == 'sdcard'):
  442. return True
  443. return False
  444. def write_mcu_config(f):
  445. '''write MCU config defines'''
  446. f.write('// MCU type (ChibiOS define)\n')
  447. f.write('#define %s_MCUCONF\n' % get_config('MCU'))
  448. mcu_subtype = get_config('MCU', 1)
  449. if mcu_subtype.endswith('xx'):
  450. f.write('#define %s_MCUCONF\n\n' % mcu_subtype[:-2])
  451. f.write('#define %s\n\n' % mcu_subtype)
  452. f.write('// crystal frequency\n')
  453. f.write('#define STM32_HSECLK %sU\n\n' % get_config('OSCILLATOR_HZ'))
  454. f.write('// UART used for stdout (printf)\n')
  455. if get_config('STDOUT_SERIAL', required=False):
  456. f.write('#define HAL_STDOUT_SERIAL %s\n\n' % get_config('STDOUT_SERIAL'))
  457. f.write('// baudrate used for stdout (printf)\n')
  458. f.write('#define HAL_STDOUT_BAUDRATE %u\n\n' % get_config('STDOUT_BAUDRATE', type=int))
  459. if have_type_prefix('SDIO'):
  460. f.write('// SDIO available, enable POSIX filesystem support\n')
  461. f.write('#define USE_POSIX\n\n')
  462. f.write('#define HAL_USE_SDC TRUE\n')
  463. build_flags.append('USE_FATFS=yes')
  464. elif have_type_prefix('SDMMC'):
  465. f.write('// SDMMC available, enable POSIX filesystem support\n')
  466. f.write('#define USE_POSIX\n\n')
  467. f.write('#define HAL_USE_SDC TRUE\n')
  468. f.write('#define STM32_SDC_USE_SDMMC1 TRUE\n')
  469. build_flags.append('USE_FATFS=yes')
  470. elif has_sdcard_spi():
  471. f.write('// MMC via SPI available, enable POSIX filesystem support\n')
  472. f.write('#define USE_POSIX\n\n')
  473. f.write('#define HAL_USE_MMC_SPI TRUE\n')
  474. f.write('#define HAL_USE_SDC FALSE\n')
  475. f.write('#define HAL_SDCARD_SPI_HOOK TRUE\n')
  476. build_flags.append('USE_FATFS=yes')
  477. else:
  478. f.write('#define HAL_USE_SDC FALSE\n')
  479. build_flags.append('USE_FATFS=no')
  480. env_vars['DISABLE_SCRIPTING'] = True
  481. if 'OTG1' in bytype:
  482. f.write('#define STM32_USB_USE_OTG1 TRUE\n')
  483. f.write('#define HAL_USE_USB TRUE\n')
  484. f.write('#define HAL_USE_SERIAL_USB TRUE\n')
  485. if 'OTG2' in bytype:
  486. f.write('#define STM32_USB_USE_OTG2 TRUE\n')
  487. if have_type_prefix('CAN') and not 'AP_PERIPH' in env_vars:
  488. enable_can(f)
  489. if get_config('PROCESS_STACK', required=False):
  490. env_vars['PROCESS_STACK'] = get_config('PROCESS_STACK')
  491. else:
  492. env_vars['PROCESS_STACK'] = "0x2000"
  493. if get_config('MAIN_STACK', required=False):
  494. env_vars['MAIN_STACK'] = get_config('MAIN_STACK')
  495. else:
  496. env_vars['MAIN_STACK'] = "0x400"
  497. if get_config('IOMCU_FW', required=False):
  498. env_vars['IOMCU_FW'] = get_config('IOMCU_FW')
  499. else:
  500. env_vars['IOMCU_FW'] = 0
  501. if get_config('PERIPH_FW', required=False):
  502. env_vars['PERIPH_FW'] = get_config('PERIPH_FW')
  503. else:
  504. env_vars['PERIPH_FW'] = 0
  505. # write any custom STM32 defines
  506. for d in alllines:
  507. if d.startswith('STM32_'):
  508. f.write('#define %s\n' % d)
  509. if d.startswith('define '):
  510. f.write('#define %s\n' % d[7:])
  511. flash_size = get_config('FLASH_SIZE_KB', type=int)
  512. f.write('#define BOARD_FLASH_SIZE %u\n' % flash_size)
  513. env_vars['BOARD_FLASH_SIZE'] = flash_size
  514. f.write('#define CRT1_AREAS_NUMBER 1\n')
  515. flash_reserve_start = get_config(
  516. 'FLASH_RESERVE_START_KB', default=16, type=int)
  517. f.write('\n// location of loaded firmware\n')
  518. f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024))
  519. if args.bootloader:
  520. f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int))
  521. f.write('\n')
  522. ram_map = get_mcu_config('RAM_MAP', True)
  523. f.write('// memory regions\n')
  524. regions = []
  525. total_memory = 0
  526. for (address, size, flags) in ram_map:
  527. regions.append('{(void*)0x%08x, 0x%08x, 0x%02x }' % (address, size*1024, flags))
  528. total_memory += size
  529. f.write('#define HAL_MEMORY_REGIONS %s\n' % ', '.join(regions))
  530. f.write('#define HAL_MEMORY_TOTAL_KB %u\n' % total_memory)
  531. f.write('\n// CPU serial number (12 bytes)\n')
  532. f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
  533. f.write('\n// APJ board ID (for bootloaders)\n')
  534. f.write('#define APJ_BOARD_ID %s\n' % get_config('APJ_BOARD_ID'))
  535. lib = get_mcu_lib(mcu_type)
  536. build_info = lib.build
  537. if mcu_series.startswith("STM32F1"):
  538. cortex = "cortex-m3"
  539. env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex]
  540. build_info['MCU'] = cortex
  541. else:
  542. cortex = "cortex-m4"
  543. env_vars['CPU_FLAGS'] = [ "-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"]
  544. build_info['MCU'] = cortex
  545. if not args.bootloader:
  546. env_vars['CPU_FLAGS'].append('-u_printf_float')
  547. build_info['ENV_UDEFS'] = "-DCHPRINTF_USE_FLOAT=1"
  548. # setup build variables
  549. for v in build_info.keys():
  550. build_flags.append('%s=%s' % (v, build_info[v]))
  551. # setup for bootloader build
  552. if args.bootloader:
  553. f.write('''
  554. #define HAL_BOOTLOADER_BUILD TRUE
  555. #define HAL_USE_ADC FALSE
  556. #define HAL_USE_EXT FALSE
  557. #define HAL_NO_UARTDRIVER
  558. #define HAL_NO_PRINTF
  559. #define HAL_NO_CCM
  560. #define CH_DBG_STATISTICS FALSE
  561. #define CH_CFG_USE_TM FALSE
  562. #define CH_CFG_USE_REGISTRY FALSE
  563. #define CH_CFG_USE_WAITEXIT FALSE
  564. #define CH_CFG_USE_DYNAMIC FALSE
  565. #define CH_CFG_USE_MEMPOOLS FALSE
  566. #define CH_CFG_USE_OBJ_FIFOS FALSE
  567. #define CH_DBG_FILL_THREADS FALSE
  568. #define CH_CFG_USE_SEMAPHORES FALSE
  569. #define CH_CFG_USE_HEAP FALSE
  570. #define CH_CFG_USE_MUTEXES FALSE
  571. #define CH_CFG_USE_CONDVARS FALSE
  572. #define CH_CFG_USE_CONDVARS_TIMEOUT FALSE
  573. #define CH_CFG_USE_EVENTS FALSE
  574. #define CH_CFG_USE_EVENTS_TIMEOUT FALSE
  575. #define CH_CFG_USE_MESSAGES FALSE
  576. #define CH_CFG_USE_MAILBOXES FALSE
  577. #define CH_CFG_USE_FACTORY FALSE
  578. #define CH_CFG_USE_MEMCORE FALSE
  579. #define HAL_USE_I2C FALSE
  580. #define HAL_USE_PWM FALSE
  581. ''')
  582. def write_ldscript(fname):
  583. '''write ldscript.ld for this board'''
  584. flash_size = get_config('FLASH_USE_MAX_KB', type=int, default=0)
  585. if flash_size == 0:
  586. flash_size = get_config('FLASH_SIZE_KB', type=int)
  587. # space to reserve for bootloader and storage at start of flash
  588. flash_reserve_start = get_config(
  589. 'FLASH_RESERVE_START_KB', default=16, type=int)
  590. env_vars['FLASH_RESERVE_START_KB'] = str(flash_reserve_start)
  591. # space to reserve for storage at end of flash
  592. flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)
  593. # ram layout
  594. ram_map = get_mcu_config('RAM_MAP', True)
  595. flash_base = 0x08000000 + flash_reserve_start * 1024
  596. if not args.bootloader:
  597. flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
  598. else:
  599. flash_length = get_config('FLASH_BOOTLOADER_LOAD_KB', type=int)
  600. print("Generating ldscript.ld")
  601. f = open(fname, 'w')
  602. f.write('''/* generated ldscript.ld */
  603. MEMORY
  604. {
  605. flash : org = 0x%08x, len = %uK
  606. ram0 : org = 0x%08x, len = %uk
  607. }
  608. INCLUDE common.ld
  609. ''' % (flash_base, flash_length, ram_map[0][0], ram_map[0][1]))
  610. def copy_common_linkerscript(outdir, hwdef):
  611. dirpath = os.path.dirname(hwdef)
  612. shutil.copy(os.path.join(dirpath, "../common/common.ld"),
  613. os.path.join(outdir, "common.ld"))
  614. def write_USB_config(f):
  615. '''write USB config defines'''
  616. if not have_type_prefix('OTG'):
  617. return
  618. f.write('// USB configuration\n')
  619. f.write('#define HAL_USB_VENDOR_ID %s\n' % get_config('USB_VENDOR', default=0x0483)) # default to ST
  620. f.write('#define HAL_USB_PRODUCT_ID %s\n' % get_config('USB_PRODUCT', default=0x5740))
  621. f.write('#define HAL_USB_STRING_MANUFACTURER "%s"\n' % get_config("USB_STRING_MANUFACTURER", default="ArduPilot"))
  622. default_product = "%BOARD%"
  623. if args.bootloader:
  624. default_product += "-BL"
  625. f.write('#define HAL_USB_STRING_PRODUCT "%s"\n' % get_config("USB_STRING_PRODUCT", default=default_product))
  626. f.write('#define HAL_USB_STRING_SERIAL "%s"\n' % get_config("USB_STRING_SERIAL", default="%SERIAL%"))
  627. f.write('\n\n')
  628. def write_SPI_table(f):
  629. '''write SPI device table'''
  630. f.write('\n// SPI device table\n')
  631. devlist = []
  632. for dev in spidev:
  633. if len(dev) != 7:
  634. print("Badly formed SPIDEV line %s" % dev)
  635. name = '"' + dev[0] + '"'
  636. bus = dev[1]
  637. devid = dev[2]
  638. cs = dev[3]
  639. mode = dev[4]
  640. lowspeed = dev[5]
  641. highspeed = dev[6]
  642. if not bus.startswith('SPI') or not bus in spi_list:
  643. error("Bad SPI bus in SPIDEV line %s" % dev)
  644. if not devid.startswith('DEVID') or not is_int(devid[5:]):
  645. error("Bad DEVID in SPIDEV line %s" % dev)
  646. if not cs in bylabel or not bylabel[cs].is_CS():
  647. error("Bad CS pin in SPIDEV line %s" % dev)
  648. if not mode in ['MODE0', 'MODE1', 'MODE2', 'MODE3']:
  649. error("Bad MODE in SPIDEV line %s" % dev)
  650. if not lowspeed.endswith('*MHZ') and not lowspeed.endswith('*KHZ'):
  651. error("Bad lowspeed value %s in SPIDEV line %s" % (lowspeed, dev))
  652. if not highspeed.endswith('*MHZ') and not highspeed.endswith('*KHZ'):
  653. error("Bad highspeed value %s in SPIDEV line %s" % (highspeed,
  654. dev))
  655. cs_pin = bylabel[cs]
  656. pal_line = 'PAL_LINE(GPIO%s,%uU)' % (cs_pin.port, cs_pin.pin)
  657. devidx = len(devlist)
  658. f.write(
  659. '#define HAL_SPI_DEVICE%-2u SPIDesc(%-17s, %2u, %2u, %-19s, SPIDEV_%s, %7s, %7s)\n'
  660. % (devidx, name, spi_list.index(bus), int(devid[5:]), pal_line,
  661. mode, lowspeed, highspeed))
  662. devlist.append('HAL_SPI_DEVICE%u' % devidx)
  663. f.write('#define HAL_SPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
  664. def write_SPI_config(f):
  665. '''write SPI config defines'''
  666. global spi_list
  667. for t in bytype.keys():
  668. if t.startswith('SPI'):
  669. spi_list.append(t)
  670. spi_list = sorted(spi_list)
  671. if len(spi_list) == 0:
  672. f.write('#define HAL_USE_SPI FALSE\n')
  673. return
  674. devlist = []
  675. for dev in spi_list:
  676. n = int(dev[3:])
  677. devlist.append('HAL_SPI%u_CONFIG' % n)
  678. f.write(
  679. '#define HAL_SPI%u_CONFIG { &SPID%u, %u, STM32_SPI_SPI%u_DMA_STREAMS }\n'
  680. % (n, n, n, n))
  681. f.write('#define HAL_SPI_BUS_LIST %s\n\n' % ','.join(devlist))
  682. write_SPI_table(f)
  683. def parse_spi_device(dev):
  684. '''parse a SPI:xxx device item'''
  685. a = dev.split(':')
  686. if len(a) != 2:
  687. error("Bad SPI device: %s" % dev)
  688. return 'hal.spi->get_device("%s")' % a[1]
  689. def parse_i2c_device(dev):
  690. '''parse a I2C:xxx:xxx device item'''
  691. a = dev.split(':')
  692. if len(a) != 3:
  693. error("Bad I2C device: %s" % dev)
  694. busaddr = int(a[2],base=0)
  695. if a[1] == 'ALL_EXTERNAL':
  696. return ('FOREACH_I2C_EXTERNAL(b)', 'GET_I2C_DEVICE(b,0x%02x)' % (busaddr))
  697. elif a[1] == 'ALL_INTERNAL':
  698. return ('FOREACH_I2C_INTERNAL(b)', 'GET_I2C_DEVICE(b,0x%02x)' % (busaddr))
  699. elif a[1] == 'ALL':
  700. return ('FOREACH_I2C(b)', 'GET_I2C_DEVICE(b,0x%02x)' % (busaddr))
  701. busnum = int(a[1])
  702. return ('', 'GET_I2C_DEVICE(%u,0x%02x)' % (busnum, busaddr))
  703. def seen_str(dev):
  704. '''return string representation of device for checking for duplicates'''
  705. return str(dev[:2])
  706. def write_IMU_config(f):
  707. '''write IMU config defines'''
  708. global imu_list
  709. devlist = []
  710. wrapper = ''
  711. seen = set()
  712. for dev in imu_list:
  713. if seen_str(dev) in seen:
  714. error("Duplicate IMU: %s" % seen_str(dev))
  715. seen.add(seen_str(dev))
  716. driver = dev[0]
  717. for i in range(1,len(dev)):
  718. if dev[i].startswith("SPI:"):
  719. dev[i] = parse_spi_device(dev[i])
  720. elif dev[i].startswith("I2C:"):
  721. (wrapper, dev[i]) = parse_i2c_device(dev[i])
  722. n = len(devlist)+1
  723. devlist.append('HAL_INS_PROBE%u' % n)
  724. f.write(
  725. '#define HAL_INS_PROBE%u %s ADD_BACKEND(AP_InertialSensor_%s::probe(*this,%s))\n'
  726. % (n, wrapper, driver, ','.join(dev[1:])))
  727. if len(devlist) > 0:
  728. f.write('#define HAL_INS_PROBE_LIST %s\n\n' % ';'.join(devlist))
  729. def write_MAG_config(f):
  730. '''write MAG config defines'''
  731. global compass_list
  732. devlist = []
  733. seen = set()
  734. for dev in compass_list:
  735. if seen_str(dev) in seen:
  736. error("Duplicate MAG: %s" % seen_str(dev))
  737. seen.add(seen_str(dev))
  738. driver = dev[0]
  739. probe = 'probe'
  740. wrapper = ''
  741. a = driver.split(':')
  742. driver = a[0]
  743. if len(a) > 1 and a[1].startswith('probe'):
  744. probe = a[1]
  745. for i in range(1,len(dev)):
  746. if dev[i].startswith("SPI:"):
  747. dev[i] = parse_spi_device(dev[i])
  748. elif dev[i].startswith("I2C:"):
  749. (wrapper, dev[i]) = parse_i2c_device(dev[i])
  750. n = len(devlist)+1
  751. devlist.append('HAL_MAG_PROBE%u' % n)
  752. f.write(
  753. '#define HAL_MAG_PROBE%u %s ADD_BACKEND(DRIVER_%s, AP_Compass_%s::%s(%s))\n'
  754. % (n, wrapper, driver, driver, probe, ','.join(dev[1:])))
  755. if len(devlist) > 0:
  756. f.write('#define HAL_MAG_PROBE_LIST %s\n\n' % ';'.join(devlist))
  757. def write_BARO_config(f):
  758. '''write barometer config defines'''
  759. global baro_list
  760. devlist = []
  761. seen = set()
  762. for dev in baro_list:
  763. if seen_str(dev) in seen:
  764. error("Duplicate BARO: %s" % seen_str(dev))
  765. seen.add(seen_str(dev))
  766. driver = dev[0]
  767. probe = 'probe'
  768. wrapper = ''
  769. a = driver.split(':')
  770. driver = a[0]
  771. if len(a) > 1 and a[1].startswith('probe'):
  772. probe = a[1]
  773. for i in range(1,len(dev)):
  774. if dev[i].startswith("SPI:"):
  775. dev[i] = parse_spi_device(dev[i])
  776. elif dev[i].startswith("I2C:"):
  777. (wrapper, dev[i]) = parse_i2c_device(dev[i])
  778. if dev[i].startswith('hal.i2c_mgr'):
  779. dev[i] = 'std::move(%s)' % dev[i]
  780. n = len(devlist)+1
  781. devlist.append('HAL_BARO_PROBE%u' % n)
  782. f.write(
  783. '#define HAL_BARO_PROBE%u %s ADD_BACKEND(AP_Baro_%s::%s(*this,%s))\n'
  784. % (n, wrapper, driver, probe, ','.join(dev[1:])))
  785. if len(devlist) > 0:
  786. f.write('#define HAL_BARO_PROBE_LIST %s\n\n' % ';'.join(devlist))
  787. def get_gpio_bylabel(label):
  788. '''get GPIO(n) setting on a pin label, or -1'''
  789. p = bylabel.get(label)
  790. if p is None:
  791. return -1
  792. return p.extra_value('GPIO', type=int, default=-1)
  793. def get_extra_bylabel(label, name, default=None):
  794. '''get extra setting for a label by name'''
  795. p = bylabel.get(label)
  796. if p is None:
  797. return default
  798. return p.extra_value(name, type=str, default=default)
  799. def write_UART_config(f):
  800. '''write UART config defines'''
  801. if get_config('UART_ORDER', required=False) is None:
  802. return
  803. uart_list = config['UART_ORDER']
  804. f.write('\n// UART configuration\n')
  805. # write out driver declarations for HAL_ChibOS_Class.cpp
  806. devnames = "ABCDEFGH"
  807. sdev = 0
  808. idx = 0
  809. for dev in uart_list:
  810. if dev == 'EMPTY':
  811. f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' %
  812. (devnames[idx], devnames[idx]))
  813. else:
  814. f.write(
  815. '#define HAL_UART%s_DRIVER ChibiOS::UARTDriver uart%sDriver(%u)\n'
  816. % (devnames[idx], devnames[idx], sdev))
  817. sdev += 1
  818. idx += 1
  819. for idx in range(len(uart_list), len(devnames)):
  820. f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' %
  821. (devnames[idx], devnames[idx]))
  822. if 'IOMCU_UART' in config:
  823. f.write('#define HAL_WITH_IO_MCU 1\n')
  824. idx = len(uart_list)
  825. f.write('#define HAL_UART_IOMCU_IDX %u\n' % idx)
  826. f.write(
  827. '#define HAL_UART_IO_DRIVER ChibiOS::UARTDriver uart_io(HAL_UART_IOMCU_IDX)\n'
  828. )
  829. uart_list.append(config['IOMCU_UART'][0])
  830. f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n') # make the assumption that IO gurantees servo monitoring
  831. else:
  832. f.write('#define HAL_WITH_IO_MCU 0\n')
  833. f.write('\n')
  834. need_uart_driver = False
  835. OTG2_index = None
  836. devlist = []
  837. for dev in uart_list:
  838. if dev.startswith('UART'):
  839. n = int(dev[4:])
  840. elif dev.startswith('USART'):
  841. n = int(dev[5:])
  842. elif dev.startswith('OTG'):
  843. n = int(dev[3:])
  844. elif dev.startswith('EMPTY'):
  845. continue
  846. else:
  847. error("Invalid element %s in UART_ORDER" % dev)
  848. devlist.append('HAL_%s_CONFIG' % dev)
  849. if dev + "_RTS" in bylabel:
  850. p = bylabel[dev + '_RTS']
  851. rts_line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin)
  852. else:
  853. rts_line = "0"
  854. if dev.startswith('OTG2'):
  855. f.write(
  856. '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, true, false, 0, 0, false, 0, 0}\n'
  857. % dev)
  858. OTG2_index = uart_list.index(dev)
  859. elif dev.startswith('OTG'):
  860. f.write(
  861. '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, true, false, 0, 0, false, 0, 0}\n'
  862. % dev)
  863. else:
  864. need_uart_driver = True
  865. f.write(
  866. "#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, false, "
  867. % (dev, n))
  868. if mcu_series.startswith("STM32F1"):
  869. f.write("%s, " % rts_line)
  870. else:
  871. f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, " %
  872. (dev, dev, rts_line))
  873. # add inversion pins, if any
  874. f.write("%d, " % get_gpio_bylabel(dev + "_RXINV"))
  875. f.write("%s, " % get_extra_bylabel(dev + "_RXINV", "POL", "0"))
  876. f.write("%d, " % get_gpio_bylabel(dev + "_TXINV"))
  877. f.write("%s}\n" % get_extra_bylabel(dev + "_TXINV", "POL", "0"))
  878. if OTG2_index is not None:
  879. f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index)
  880. f.write('''
  881. #if HAL_WITH_UAVCAN
  882. #ifndef HAL_OTG2_PROTOCOL
  883. #define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN
  884. #endif
  885. #define HAL_SERIAL%d_PROTOCOL HAL_OTG2_PROTOCOL
  886. #define HAL_SERIAL%d_BAUD 115200
  887. #endif
  888. ''' % (OTG2_index, OTG2_index))
  889. f.write('#define HAL_HAVE_DUAL_USB_CDC 1\n')
  890. f.write('#define HAL_UART_DEVICE_LIST %s\n\n' % ','.join(devlist))
  891. if not need_uart_driver and not args.bootloader:
  892. f.write('''
  893. #ifndef HAL_USE_SERIAL
  894. #define HAL_USE_SERIAL HAL_USE_SERIAL_USB
  895. #endif
  896. ''')
  897. def write_UART_config_bootloader(f):
  898. '''write UART config defines'''
  899. if get_config('UART_ORDER', required=False) is None:
  900. return
  901. uart_list = config['UART_ORDER']
  902. f.write('\n// UART configuration\n')
  903. devlist = []
  904. have_uart = False
  905. OTG2_index = None
  906. for u in uart_list:
  907. if u.startswith('OTG2'):
  908. devlist.append('(BaseChannel *)&SDU2')
  909. OTG2_index = uart_list.index(u)
  910. elif u.startswith('OTG'):
  911. devlist.append('(BaseChannel *)&SDU1')
  912. else:
  913. unum = int(u[-1])
  914. devlist.append('(BaseChannel *)&SD%u' % unum)
  915. have_uart = True
  916. f.write('#define BOOTLOADER_DEV_LIST %s\n' % ','.join(devlist))
  917. if OTG2_index is not None:
  918. f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index)
  919. if not have_uart:
  920. f.write('''
  921. #ifndef HAL_USE_SERIAL
  922. #define HAL_USE_SERIAL FALSE
  923. #endif
  924. ''')
  925. def write_I2C_config(f):
  926. '''write I2C config defines'''
  927. if not have_type_prefix('I2C'):
  928. print("No I2C peripherals")
  929. f.write('''
  930. #ifndef HAL_USE_I2C
  931. #define HAL_USE_I2C FALSE
  932. #endif
  933. ''')
  934. return
  935. if not 'I2C_ORDER' in config:
  936. print("Missing I2C_ORDER config")
  937. return
  938. i2c_list = config['I2C_ORDER']
  939. f.write('// I2C configuration\n')
  940. if len(i2c_list) == 0:
  941. error("I2C_ORDER invalid")
  942. devlist = []
  943. # write out config structures
  944. for dev in i2c_list:
  945. if not dev.startswith('I2C') or dev[3] not in "1234":
  946. error("Bad I2C_ORDER element %s" % dev)
  947. n = int(dev[3:])
  948. devlist.append('HAL_I2C%u_CONFIG' % n)
  949. f.write('''
  950. #if defined(STM32_I2C_I2C%u_RX_DMA_STREAM) && defined(STM32_I2C_I2C%u_TX_DMA_STREAM)
  951. #define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM, HAL_GPIO_PIN_I2C%u_SCL, HAL_GPIO_PIN_I2C%u_SDA }
  952. #else
  953. #define HAL_I2C%u_CONFIG { &I2CD%u, SHARED_DMA_NONE, SHARED_DMA_NONE, HAL_GPIO_PIN_I2C%u_SCL, HAL_GPIO_PIN_I2C%u_SDA }
  954. #endif
  955. '''
  956. % (n, n, n, n, n, n, n, n, n, n, n, n))
  957. f.write('\n#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
  958. def parse_timer(str):
  959. '''parse timer channel string, i.e TIM8_CH2N'''
  960. result = re.match(r'TIM([0-9]*)_CH([1234])(N?)', str)
  961. if result:
  962. tim = int(result.group(1))
  963. chan = int(result.group(2))
  964. compl = result.group(3) == 'N'
  965. if tim < 1 or tim > 17:
  966. error("Bad timer number %s in %s" % (tim, str))
  967. return (tim, chan, compl)
  968. else:
  969. error("Bad timer definition %s" % str)
  970. def write_PWM_config(f):
  971. '''write PWM config defines'''
  972. rc_in = None
  973. rc_in_int = None
  974. alarm = None
  975. pwm_out = []
  976. pwm_timers = []
  977. for l in bylabel.keys():
  978. p = bylabel[l]
  979. if p.type.startswith('TIM'):
  980. if p.has_extra('RCIN'):
  981. rc_in = p
  982. elif p.has_extra('RCININT'):
  983. rc_in_int = p
  984. elif p.has_extra('ALARM'):
  985. alarm = p
  986. else:
  987. if p.extra_value('PWM', type=int) is not None:
  988. pwm_out.append(p)
  989. if p.type not in pwm_timers:
  990. pwm_timers.append(p.type)
  991. if not pwm_out and not alarm:
  992. print("No PWM output defined")
  993. f.write('''
  994. #ifndef HAL_USE_PWM
  995. #define HAL_USE_PWM FALSE
  996. #endif
  997. ''')
  998. if rc_in is not None:
  999. (n, chan, compl) = parse_timer(rc_in.label)
  1000. if compl:
  1001. # it is an inverted channel
  1002. f.write('#define HAL_RCIN_IS_INVERTED\n')
  1003. if chan not in [1, 2]:
  1004. error(
  1005. "Bad channel number, only channel 1 and 2 supported for RCIN")
  1006. f.write('// RC input config\n')
  1007. f.write('#define HAL_USE_ICU TRUE\n')
  1008. f.write('#define STM32_ICU_USE_TIM%u TRUE\n' % n)
  1009. f.write('#define RCIN_ICU_TIMER ICUD%u\n' % n)
  1010. f.write('#define RCIN_ICU_CHANNEL ICU_CHANNEL_%u\n' % chan)
  1011. f.write('#define STM32_RCIN_DMA_STREAM STM32_TIM_TIM%u_CH%u_DMA_STREAM\n' % (n, chan))
  1012. f.write('#define STM32_RCIN_DMA_CHANNEL STM32_TIM_TIM%u_CH%u_DMA_CHAN\n' % (n, chan))
  1013. f.write('\n')
  1014. if rc_in_int is not None:
  1015. (n, chan, compl) = parse_timer(rc_in_int.label)
  1016. if compl:
  1017. error('Complementary channel is not supported for RCININT %s' % rc_in_int.label)
  1018. f.write('// RC input config\n')
  1019. f.write('#define HAL_USE_EICU TRUE\n')
  1020. f.write('#define STM32_EICU_USE_TIM%u TRUE\n' % n)
  1021. f.write('#define RCININT_EICU_TIMER EICUD%u\n' % n)
  1022. f.write('#define RCININT_EICU_CHANNEL EICU_CHANNEL_%u\n' % chan)
  1023. f.write('\n')
  1024. if alarm is not None:
  1025. (n, chan, compl) = parse_timer(alarm.label)
  1026. if compl:
  1027. error("Complementary channel is not supported for ALARM %s" % alarm.label)
  1028. f.write('\n')
  1029. f.write('// Alarm PWM output config\n')
  1030. f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
  1031. f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
  1032. chan_mode = [
  1033. 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED',
  1034. 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED'
  1035. ]
  1036. chan_mode[chan - 1] = 'PWM_OUTPUT_ACTIVE_HIGH'
  1037. pwm_clock = 1000000
  1038. period = 1000
  1039. f.write('''#define HAL_PWM_ALARM \\
  1040. { /* pwmGroup */ \\
  1041. %u, /* Timer channel */ \\
  1042. { /* PWMConfig */ \\
  1043. %u, /* PWM clock frequency. */ \\
  1044. %u, /* Initial PWM period 20ms. */ \\
  1045. NULL, /* no callback */ \\
  1046. { /* Channel Config */ \\
  1047. {%s, NULL}, \\
  1048. {%s, NULL}, \\
  1049. {%s, NULL}, \\
  1050. {%s, NULL} \\
  1051. }, \\
  1052. 0, 0 \\
  1053. }, \\
  1054. &PWMD%u /* PWMDriver* */ \\
  1055. }\n''' %
  1056. (chan-1, pwm_clock, period, chan_mode[0],
  1057. chan_mode[1], chan_mode[2], chan_mode[3], n))
  1058. else:
  1059. f.write('\n')
  1060. f.write('// No Alarm output pin defined\n')
  1061. f.write('#undef HAL_PWM_ALARM\n')
  1062. f.write('\n')
  1063. f.write('// PWM timer config\n')
  1064. for t in sorted(pwm_timers):
  1065. n = int(t[3:])
  1066. f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
  1067. f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
  1068. f.write('\n')
  1069. f.write('// PWM output config\n')
  1070. groups = []
  1071. for t in sorted(pwm_timers):
  1072. group = len(groups) + 1
  1073. n = int(t[3:])
  1074. chan_list = [255, 255, 255, 255]
  1075. chan_mode = [
  1076. 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED',
  1077. 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED'
  1078. ]
  1079. alt_functions = [ 0, 0, 0, 0 ]
  1080. pal_lines = [ '0', '0', '0', '0' ]
  1081. for p in pwm_out:
  1082. if p.type != t:
  1083. continue
  1084. (n, chan, compl) = parse_timer(p.label)
  1085. pwm = p.extra_value('PWM', type=int)
  1086. chan_list[chan - 1] = pwm - 1
  1087. if compl:
  1088. chan_mode[chan - 1] = 'PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH'
  1089. else:
  1090. chan_mode[chan - 1] = 'PWM_OUTPUT_ACTIVE_HIGH'
  1091. alt_functions[chan - 1] = p.af
  1092. pal_lines[chan - 1] = 'PAL_LINE(GPIO%s, %uU)' % (p.port, p.pin)
  1093. groups.append('HAL_PWM_GROUP%u' % group)
  1094. if n in [1, 8]:
  1095. # only the advanced timers do 8MHz clocks
  1096. advanced_timer = 'true'
  1097. else:
  1098. advanced_timer = 'false'
  1099. pwm_clock = 1000000
  1100. period = 20000 * pwm_clock / 1000000
  1101. f.write('''#if defined(STM32_TIM_TIM%u_UP_DMA_STREAM) && defined(STM32_TIM_TIM%u_UP_DMA_CHAN)
  1102. # define HAL_PWM%u_DMA_CONFIG true, STM32_TIM_TIM%u_UP_DMA_STREAM, STM32_TIM_TIM%u_UP_DMA_CHAN
  1103. #else
  1104. # define HAL_PWM%u_DMA_CONFIG false, 0, 0
  1105. #endif\n''' % (n, n, n, n, n, n))
  1106. f.write('''#define HAL_PWM_GROUP%u { %s, \\
  1107. {%u, %u, %u, %u}, \\
  1108. /* Group Initial Config */ \\
  1109. { \\
  1110. %u, /* PWM clock frequency. */ \\
  1111. %u, /* Initial PWM period 20ms. */ \\
  1112. NULL, /* no callback */ \\
  1113. { \\
  1114. /* Channel Config */ \\
  1115. {%s, NULL}, \\
  1116. {%s, NULL}, \\
  1117. {%s, NULL}, \\
  1118. {%s, NULL} \\
  1119. }, 0, 0}, &PWMD%u, \\
  1120. HAL_PWM%u_DMA_CONFIG, \\
  1121. { %u, %u, %u, %u }, \\
  1122. { %s, %s, %s, %s }}\n''' %
  1123. (group, advanced_timer,
  1124. chan_list[0], chan_list[1], chan_list[2], chan_list[3],
  1125. pwm_clock, period,
  1126. chan_mode[0], chan_mode[1], chan_mode[2], chan_mode[3],
  1127. n, n,
  1128. alt_functions[0], alt_functions[1], alt_functions[2], alt_functions[3],
  1129. pal_lines[0], pal_lines[1], pal_lines[2], pal_lines[3]))
  1130. f.write('#define HAL_PWM_GROUPS %s\n\n' % ','.join(groups))
  1131. def write_ADC_config(f):
  1132. '''write ADC config defines'''
  1133. f.write('// ADC config\n')
  1134. adc_chans = []
  1135. for l in bylabel:
  1136. p = bylabel[l]
  1137. if not p.type.startswith('ADC'):
  1138. continue
  1139. chan = get_ADC1_chan(mcu_type, p.portpin)
  1140. scale = p.extra_value('SCALE', default=None)
  1141. if p.label == 'VDD_5V_SENS':
  1142. f.write('#define ANALOG_VCC_5V_PIN %u\n' % chan)
  1143. f.write('#define HAL_HAVE_BOARD_VOLTAGE 1\n')
  1144. if p.label == 'FMU_SERVORAIL_VCC_SENS':
  1145. f.write('#define FMU_SERVORAIL_ADC_CHAN %u\n' % chan)
  1146. f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n')
  1147. adc_chans.append((chan, scale, p.label, p.portpin))
  1148. adc_chans = sorted(adc_chans)
  1149. vdd = get_config('STM32_VDD')
  1150. if vdd[-1] == 'U':
  1151. vdd = vdd[:-1]
  1152. vdd = float(vdd) * 0.01
  1153. f.write('#define HAL_ANALOG_PINS { \\\n')
  1154. for (chan, scale, label, portpin) in adc_chans:
  1155. scale_str = '%.2f/4096' % vdd
  1156. if scale is not None and scale != '1':
  1157. scale_str = scale + '*' + scale_str
  1158. f.write('{ %2u, %12s }, /* %s %s */ \\\n' % (chan, scale_str, portpin,
  1159. label))
  1160. f.write('}\n\n')
  1161. def write_GPIO_config(f):
  1162. '''write GPIO config defines'''
  1163. f.write('// GPIO config\n')
  1164. gpios = []
  1165. gpioset = set()
  1166. for l in bylabel:
  1167. p = bylabel[l]
  1168. gpio = p.extra_value('GPIO', type=int)
  1169. if gpio is None:
  1170. continue
  1171. if gpio in gpioset:
  1172. error("Duplicate GPIO value %u" % gpio)
  1173. gpioset.add(gpio)
  1174. # see if it is also a PWM pin
  1175. pwm = p.extra_value('PWM', type=int, default=0)
  1176. port = p.port
  1177. pin = p.pin
  1178. gpios.append((gpio, pwm, port, pin, p))
  1179. gpios = sorted(gpios)
  1180. for (gpio, pwm, port, pin, p) in gpios:
  1181. f.write('#define HAL_GPIO_LINE_GPIO%u PAL_LINE(GPIO%s, %2uU)\n' % (gpio, port, pin))
  1182. f.write('#define HAL_GPIO_PINS { \\\n')
  1183. for (gpio, pwm, port, pin, p) in gpios:
  1184. f.write('{ %3u, true, %2u, PAL_LINE(GPIO%s, %2uU)}, /* %s */ \\\n' %
  1185. (gpio, pwm, port, pin, p))
  1186. # and write #defines for use by config code
  1187. f.write('}\n\n')
  1188. f.write('// full pin define list\n')
  1189. last_label = None
  1190. for l in sorted(list(set(bylabel.keys()))):
  1191. p = bylabel[l]
  1192. label = p.label
  1193. label = label.replace('-', '_')
  1194. if label == last_label:
  1195. continue
  1196. last_label = label
  1197. f.write('#define HAL_GPIO_PIN_%-20s PAL_LINE(GPIO%s,%uU)\n' %
  1198. (label, p.port, p.pin))
  1199. f.write('\n')
  1200. def bootloader_path():
  1201. # always embed a bootloader if it is available
  1202. this_dir = os.path.realpath(__file__)
  1203. rootdir = os.path.relpath(os.path.join(this_dir, "../../../../.."))
  1204. hwdef_dirname = os.path.basename(os.path.dirname(args.hwdef))
  1205. bootloader_filename = "%s_bl.bin" % (hwdef_dirname,)
  1206. bootloader_path = os.path.join(rootdir,
  1207. "Tools",
  1208. "bootloaders",
  1209. bootloader_filename)
  1210. if os.path.exists(bootloader_path):
  1211. return os.path.realpath(bootloader_path)
  1212. return None
  1213. def add_bootloader():
  1214. '''added bootloader to ROMFS'''
  1215. bp = bootloader_path()
  1216. if bp is not None:
  1217. romfs["bootloader.bin"] = bp
  1218. def write_ROMFS(outdir):
  1219. '''create ROMFS embedded header'''
  1220. romfs_list = []
  1221. for k in romfs.keys():
  1222. romfs_list.append((k, romfs[k]))
  1223. env_vars['ROMFS_FILES'] = romfs_list
  1224. def setup_apj_IDs():
  1225. '''setup the APJ board IDs'''
  1226. env_vars['APJ_BOARD_ID'] = get_config('APJ_BOARD_ID')
  1227. env_vars['APJ_BOARD_TYPE'] = get_config('APJ_BOARD_TYPE', default=mcu_type)
  1228. def write_peripheral_enable(f):
  1229. '''write peripheral enable lines'''
  1230. f.write('// peripherals enabled\n')
  1231. for type in sorted(bytype.keys()):
  1232. if type.startswith('USART') or type.startswith('UART'):
  1233. dstr = 'STM32_SERIAL_USE_%-6s' % type
  1234. f.write('#ifndef %s\n' % dstr)
  1235. f.write('#define %s TRUE\n' % dstr)
  1236. f.write('#endif\n')
  1237. if type.startswith('SPI'):
  1238. f.write('#define STM32_SPI_USE_%s TRUE\n' % type)
  1239. if type.startswith('OTG'):
  1240. f.write('#define STM32_USB_USE_%s TRUE\n' % type)
  1241. if type.startswith('I2C'):
  1242. f.write('#define STM32_I2C_USE_%s TRUE\n' % type)
  1243. def get_dma_exclude(periph_list):
  1244. '''return list of DMA devices to exclude from DMA'''
  1245. dma_exclude = []
  1246. for periph in periph_list:
  1247. if periph not in bylabel:
  1248. continue
  1249. p = bylabel[periph]
  1250. if p.has_extra('NODMA'):
  1251. dma_exclude.append(periph)
  1252. return dma_exclude
  1253. def write_hwdef_header(outfilename):
  1254. '''write hwdef header file'''
  1255. print("Writing hwdef setup in %s" % outfilename)
  1256. f = open(outfilename, 'w')
  1257. f.write('''/*
  1258. generated hardware definitions from hwdef.dat - DO NOT EDIT
  1259. */
  1260. #pragma once
  1261. #ifndef TRUE
  1262. #define TRUE 1
  1263. #endif
  1264. #ifndef FALSE
  1265. #define FALSE 0
  1266. #endif
  1267. ''')
  1268. write_mcu_config(f)
  1269. write_USB_config(f)
  1270. write_SPI_config(f)
  1271. write_ADC_config(f)
  1272. write_GPIO_config(f)
  1273. write_IMU_config(f)
  1274. write_MAG_config(f)
  1275. write_BARO_config(f)
  1276. write_peripheral_enable(f)
  1277. setup_apj_IDs()
  1278. dma_resolver.write_dma_header(f, periph_list, mcu_type,
  1279. dma_exclude=get_dma_exclude(periph_list),
  1280. dma_priority=get_config('DMA_PRIORITY',default='TIM* SPI*', spaces=True),
  1281. dma_noshare=get_config('DMA_NOSHARE',default='', spaces=True))
  1282. if not args.bootloader:
  1283. write_PWM_config(f)
  1284. write_I2C_config(f)
  1285. write_UART_config(f)
  1286. else:
  1287. write_UART_config_bootloader(f)
  1288. add_bootloader()
  1289. if len(romfs) > 0:
  1290. f.write('#define HAL_HAVE_AP_ROMFS_EMBEDDED_H 1\n')
  1291. if mcu_series.startswith('STM32F1'):
  1292. f.write('''
  1293. /*
  1294. * I/O ports initial setup, this configuration is established soon after reset
  1295. * in the initialization code.
  1296. * Please refer to the STM32 Reference Manual for details.
  1297. */
  1298. #define PIN_MODE_OUTPUT_PP(n) (0 << (((n) & 7) * 4))
  1299. #define PIN_MODE_OUTPUT_OD(n) (4 << (((n) & 7) * 4))
  1300. #define PIN_MODE_AF_PP(n) (8 << (((n) & 7) * 4))
  1301. #define PIN_MODE_AF_OD(n) (12 << (((n) & 7) * 4))
  1302. #define PIN_MODE_ANALOG(n) (0 << (((n) & 7) * 4))
  1303. #define PIN_MODE_NOPULL(n) (4 << (((n) & 7) * 4))
  1304. #define PIN_MODE_PUD(n) (8 << (((n) & 7) * 4))
  1305. #define PIN_SPEED_MEDIUM(n) (1 << (((n) & 7) * 4))
  1306. #define PIN_SPEED_LOW(n) (2 << (((n) & 7) * 4))
  1307. #define PIN_SPEED_HIGH(n) (3 << (((n) & 7) * 4))
  1308. #define PIN_ODR_HIGH(n) (1 << (((n) & 15)))
  1309. #define PIN_ODR_LOW(n) (0 << (((n) & 15)))
  1310. #define PIN_PULLUP(n) (1 << (((n) & 15)))
  1311. #define PIN_PULLDOWN(n) (0 << (((n) & 15)))
  1312. #define PIN_UNDEFINED(n) PIN_INPUT_PUD(n)
  1313. ''')
  1314. else:
  1315. f.write('''
  1316. /*
  1317. * I/O ports initial setup, this configuration is established soon after reset
  1318. * in the initialization code.
  1319. * Please refer to the STM32 Reference Manual for details.
  1320. */
  1321. #define PIN_MODE_INPUT(n) (0U << ((n) * 2U))
  1322. #define PIN_MODE_OUTPUT(n) (1U << ((n) * 2U))
  1323. #define PIN_MODE_ALTERNATE(n) (2U << ((n) * 2U))
  1324. #define PIN_MODE_ANALOG(n) (3U << ((n) * 2U))
  1325. #define PIN_ODR_LOW(n) (0U << (n))
  1326. #define PIN_ODR_HIGH(n) (1U << (n))
  1327. #define PIN_OTYPE_PUSHPULL(n) (0U << (n))
  1328. #define PIN_OTYPE_OPENDRAIN(n) (1U << (n))
  1329. #define PIN_OSPEED_VERYLOW(n) (0U << ((n) * 2U))
  1330. #define PIN_OSPEED_LOW(n) (1U << ((n) * 2U))
  1331. #define PIN_OSPEED_MEDIUM(n) (2U << ((n) * 2U))
  1332. #define PIN_OSPEED_HIGH(n) (3U << ((n) * 2U))
  1333. #define PIN_PUPDR_FLOATING(n) (0U << ((n) * 2U))
  1334. #define PIN_PUPDR_PULLUP(n) (1U << ((n) * 2U))
  1335. #define PIN_PUPDR_PULLDOWN(n) (2U << ((n) * 2U))
  1336. #define PIN_AFIO_AF(n, v) ((v) << (((n) % 8U) * 4U))
  1337. ''')
  1338. for port in sorted(ports):
  1339. f.write("/* PORT%s:\n" % port)
  1340. for pin in range(pincount[port]):
  1341. p = portmap[port][pin]
  1342. if p.label is not None:
  1343. f.write(" %s\n" % p)
  1344. f.write("*/\n\n")
  1345. if pincount[port] == 0:
  1346. # handle blank ports
  1347. for vtype in vtypes:
  1348. f.write("#define VAL_GPIO%s_%-7s 0x0\n" % (port,
  1349. vtype))
  1350. f.write("\n\n\n")
  1351. continue
  1352. for vtype in vtypes:
  1353. f.write("#define VAL_GPIO%s_%-7s (" % (p.port, vtype))
  1354. first = True
  1355. for pin in range(pincount[port]):
  1356. p = portmap[port][pin]
  1357. modefunc = getattr(p, "get_" + vtype)
  1358. v = modefunc()
  1359. if v is None:
  1360. continue
  1361. if not first:
  1362. f.write(" | \\\n ")
  1363. f.write(v)
  1364. first = False
  1365. if first:
  1366. # there were no pin definitions, use 0
  1367. f.write("0")
  1368. f.write(")\n\n")
  1369. def build_peripheral_list():
  1370. '''build a list of peripherals for DMA resolver to work on'''
  1371. peripherals = []
  1372. done = set()
  1373. prefixes = ['SPI', 'USART', 'UART', 'I2C']
  1374. for p in allpins:
  1375. type = p.type
  1376. if type in done:
  1377. continue
  1378. for prefix in prefixes:
  1379. if type.startswith(prefix):
  1380. ptx = type + "_TX"
  1381. prx = type + "_RX"
  1382. peripherals.append(ptx)
  1383. peripherals.append(prx)
  1384. if not ptx in bylabel:
  1385. bylabel[ptx] = p
  1386. if not prx in bylabel:
  1387. bylabel[prx] = p
  1388. if type.startswith('ADC'):
  1389. peripherals.append(type)
  1390. if type.startswith('SDIO') or type.startswith('SDMMC'):
  1391. if not mcu_series.startswith("STM32H7"):
  1392. peripherals.append(type)
  1393. if type.startswith('TIM'):
  1394. if p.has_extra('RCIN'):
  1395. label = p.label
  1396. if label[-1] == 'N':
  1397. label = label[:-1]
  1398. peripherals.append(label)
  1399. elif not p.has_extra('ALARM') and not p.has_extra('RCININT'):
  1400. # get the TIMn_UP DMA channels for DShot
  1401. label = type + '_UP'
  1402. if not label in peripherals and not p.has_extra('NODMA'):
  1403. peripherals.append(label)
  1404. done.add(type)
  1405. return peripherals
  1406. def write_env_py(filename):
  1407. '''write out env.py for environment variables to control the build process'''
  1408. # see if board has a defaults.parm file
  1409. defaults_filename = os.path.join(os.path.dirname(args.hwdef), 'defaults.parm')
  1410. if os.path.exists(defaults_filename) and not args.bootloader:
  1411. print("Adding defaults.parm")
  1412. env_vars['DEFAULT_PARAMETERS'] = os.path.abspath(defaults_filename)
  1413. # CHIBIOS_BUILD_FLAGS is passed to the ChibiOS makefile
  1414. env_vars['CHIBIOS_BUILD_FLAGS'] = ' '.join(build_flags)
  1415. pickle.dump(env_vars, open(filename, "wb"))
  1416. def romfs_add(romfs_filename, filename):
  1417. '''add a file to ROMFS'''
  1418. romfs[romfs_filename] = filename
  1419. def romfs_wildcard(pattern):
  1420. '''add a set of files to ROMFS by wildcard'''
  1421. base_path = os.path.join(os.path.dirname(__file__), '..', '..', '..', '..')
  1422. (pattern_dir, pattern) = os.path.split(pattern)
  1423. for f in os.listdir(os.path.join(base_path, pattern_dir)):
  1424. if fnmatch.fnmatch(f, pattern):
  1425. romfs[f] = os.path.join(pattern_dir, f)
  1426. def process_line(line):
  1427. '''process one line of pin definition file'''
  1428. global allpins, imu_list, compass_list, baro_list
  1429. a = shlex.split(line)
  1430. # keep all config lines for later use
  1431. alllines.append(line)
  1432. if a[0].startswith('P') and a[0][1] in ports and a[0] in config:
  1433. error("Pin %s redefined" % a[0])
  1434. config[a[0]] = a[1:]
  1435. if a[0] == 'MCU':
  1436. global mcu_type, mcu_series
  1437. mcu_type = a[2]
  1438. mcu_series = a[1]
  1439. setup_mcu_type_defaults()
  1440. if a[0].startswith('P') and a[0][1] in ports:
  1441. # it is a port/pin definition
  1442. try:
  1443. port = a[0][1]
  1444. pin = int(a[0][2:])
  1445. label = a[1]
  1446. type = a[2]
  1447. extra = a[3:]
  1448. except Exception:
  1449. error("Bad pin line: %s" % a)
  1450. return
  1451. p = generic_pin(port, pin, label, type, extra)
  1452. portmap[port][pin] = p
  1453. allpins.append(p)
  1454. if not type in bytype:
  1455. bytype[type] = []
  1456. bytype[type].append(p)
  1457. bylabel[label] = p
  1458. af = get_alt_function(mcu_type, a[0], label)
  1459. if af is not None:
  1460. p.af = af
  1461. if a[0] == 'SPIDEV':
  1462. spidev.append(a[1:])
  1463. if a[0] == 'IMU':
  1464. imu_list.append(a[1:])
  1465. if a[0] == 'COMPASS':
  1466. compass_list.append(a[1:])
  1467. if a[0] == 'BARO':
  1468. baro_list.append(a[1:])
  1469. if a[0] == 'ROMFS':
  1470. romfs_add(a[1],a[2])
  1471. if a[0] == 'ROMFS_WILDCARD':
  1472. romfs_wildcard(a[1])
  1473. if a[0] == 'undef':
  1474. print("Removing %s" % a[1])
  1475. config.pop(a[1], '')
  1476. bytype.pop(a[1],'')
  1477. bylabel.pop(a[1],'')
  1478. #also remove all occurences of defines in previous lines if any
  1479. for line in alllines[:]:
  1480. if line.startswith('define') and a[1] == line.split()[1]:
  1481. alllines.remove(line)
  1482. newpins = []
  1483. for pin in allpins:
  1484. if pin.type == a[1]:
  1485. continue
  1486. if pin.label == a[1]:
  1487. continue
  1488. if pin.portpin == a[1]:
  1489. continue
  1490. newpins.append(pin)
  1491. allpins = newpins
  1492. if a[1] == 'IMU':
  1493. imu_list = []
  1494. if a[1] == 'COMPASS':
  1495. compass_list = []
  1496. if a[1] == 'BARO':
  1497. baro_list = []
  1498. if a[0] == 'env':
  1499. print("Adding environment %s" % ' '.join(a[1:]))
  1500. if len(a[1:]) < 2:
  1501. error("Bad env line for %s" % a[0])
  1502. env_vars[a[1]] = ' '.join(a[2:])
  1503. def process_file(filename):
  1504. '''process a hwdef.dat file'''
  1505. try:
  1506. f = open(filename, "r")
  1507. except Exception:
  1508. error("Unable to open file %s" % filename)
  1509. for line in f.readlines():
  1510. line = line.strip()
  1511. if len(line) == 0 or line[0] == '#':
  1512. continue
  1513. a = shlex.split(line)
  1514. if a[0] == "include" and len(a) > 1:
  1515. include_file = a[1]
  1516. if include_file[0] != '/':
  1517. dir = os.path.dirname(filename)
  1518. include_file = os.path.normpath(
  1519. os.path.join(dir, include_file))
  1520. print("Including %s" % include_file)
  1521. process_file(include_file)
  1522. else:
  1523. process_line(line)
  1524. # process input file
  1525. process_file(args.hwdef)
  1526. outdir = args.outdir
  1527. if outdir is None:
  1528. outdir = '/tmp'
  1529. if not "MCU" in config:
  1530. error("Missing MCU type in config")
  1531. mcu_type = get_config('MCU', 1)
  1532. print("Setup for MCU %s" % mcu_type)
  1533. # build a list for peripherals for DMA resolver
  1534. periph_list = build_peripheral_list()
  1535. # write out hwdef.h
  1536. write_hwdef_header(os.path.join(outdir, "hwdef.h"))
  1537. # write out ldscript.ld
  1538. write_ldscript(os.path.join(outdir, "ldscript.ld"))
  1539. write_ROMFS(outdir)
  1540. # copy the shared linker script into the build directory; it must
  1541. # exist in the same directory as the ldscript.ld file we generate.
  1542. copy_common_linkerscript(outdir, args.hwdef)
  1543. write_env_py(os.path.join(outdir, "env.py"))