2 # This script can be used to Generate a basic working target from a Betaflight Configuration.
3 # The idea is that this target can be used as a starting point for full INAV target.
5 # The generated target will often be enough to get INAV working, but may need some manual editing.
7 # Betaflight Configuration files are available at https://github.com/betaflight/config
9 # Common things to look for: target.c timer definitions. You may need to change timers around
10 # to get all features working. The script will add commented out lines for all timer possibilites
26 def translateFunctionName(bffunction
, index
):
27 return bffunction
+ '_' + index
29 def translatePin(bfpin
):
30 pin
= re
.sub(r
'^([A-Z])0*(\d+)$', r
'P\1\2', bfpin
)
35 if mcu
['type'] == 'STM32F405':
36 return 'target_stm32f405xg'
39 if mcu
['type'] == 'STM32F411':
40 return 'target_stm32f411xe'
43 if mcu
['type'] == 'STM32F7X2':
44 return 'target_stm32f722xe'
47 if mcu
['type'] == 'STM32F745':
48 return 'target_stm32f745xg'
51 if mcu
['type'] == 'STM32H743':
52 return 'target_stm32h743xi'
55 if mcu
['type'] == 'AT32F435G':
56 return 'target_at32f43x_xGT7'
59 if mcu
['type'] == 'AT32F435M':
60 return 'target_at32f43x_xMT7'
62 print("Unknown MCU: %s!" % (mcu
))
65 def getPortConfig(map):
68 if mcu
['type'] == 'STM32F405':
70 #define TARGET_IO_PORTA 0xffff
71 #define TARGET_IO_PORTB 0xffff
72 #define TARGET_IO_PORTC 0xffff
73 #define TARGET_IO_PORTD 0xffff
74 #define TARGET_IO_PORTE 0xffff
75 #define TARGET_IO_PORTF 0xffff
80 if mcu
['type'] == 'STM32F411':
82 #define TARGET_IO_PORTA 0xffff
83 #define TARGET_IO_PORTB 0xffff
84 #define TARGET_IO_PORTC 0xffff
85 #define TARGET_IO_PORTD 0xffff
86 #define TARGET_IO_PORTE 0xffff
87 #define TARGET_IO_PORTF 0xffff
91 if mcu
['type'] == 'STM32F7X2':
93 #define TARGET_IO_PORTA 0xffff
94 #define TARGET_IO_PORTB 0xffff
95 #define TARGET_IO_PORTC 0xffff
96 #define TARGET_IO_PORTD 0xffff
97 #define TARGET_IO_PORTE 0xffff
98 #define TARGET_IO_PORTF 0xffff
102 if mcu
['type'] == 'STM32F745':
104 #define TARGET_IO_PORTA 0xffff
105 #define TARGET_IO_PORTB 0xffff
106 #define TARGET_IO_PORTC 0xffff
107 #define TARGET_IO_PORTD 0xffff
108 #define TARGET_IO_PORTE 0xffff
109 #define TARGET_IO_PORTF 0xffff
113 if mcu
['type'] == 'STM32H743':
115 #define TARGET_IO_PORTA 0xffff
116 #define TARGET_IO_PORTB 0xffff
117 #define TARGET_IO_PORTC 0xffff
118 #define TARGET_IO_PORTD 0xffff
119 #define TARGET_IO_PORTE 0xffff
120 #define TARGET_IO_PORTF 0xffff
121 #define TARGET_IO_PORTG 0xffff
125 if mcu
['type'] == 'AT32F435G':
126 return """#define TARGET_IO_PORTA 0xffff
127 #define TARGET_IO_PORTB 0xffff
128 #define TARGET_IO_PORTC 0xffff
129 #define TARGET_IO_PORTD 0xffff
130 #define TARGET_IO_PORTH 0xffff
134 if mcu
['type'] == 'AT32F435M':
135 return """#define TARGET_IO_PORTA 0xffff
136 #define TARGET_IO_PORTB 0xffff
137 #define TARGET_IO_PORTC 0xffff
138 #define TARGET_IO_PORTD 0xffff
139 #define TARGET_IO_PORTH 0xffff
142 print("Unknown MCU: %s" % (mcu
))
145 def writeCmakeLists(outputFolder
, map):
146 file = open(outputFolder
+ '/CMakeLists.txt', "w+")
148 t
= mcu2target(map['mcu'])
150 file.write("%s(%s SKIP_RELEASES)\n" % (t
, map['board_name']))
155 def findPinsByFunction(function
, map):
157 for func
in map['funcs']:
158 pattern
= r
"^%s" % (function
)
159 if re
.search(pattern
, func
):
160 #print ("%s: %s" % (function, func))
161 result
.append(map['funcs'][func
])
165 def findPinByFunction(function
, map):
166 if function
in map['funcs']:
167 return map['funcs'][function
]
172 def getPwmOutputCount(map):
173 motors
= findPinsByFunction("MOTOR", map)
174 servos
= findPinsByFunction("SERVO", map)
176 return len(motors
) + len(servos
)
178 def getGyroAlign(map):
179 bfalign
= map['defines'].get('GYRO_1_ALIGN', 'CW0_DEG')
181 #m = re.search(r"^CW(\d+)(FLIP)?$", bfalign)
186 # return "CW%s_DEG_FLIP" % (deg)
188 # return "CW%s_DEG" % (deg)
190 def getSerialByFunction(map, function
):
191 for serial
in map.get("serial"):
192 if map['serial'][serial
].get('FUNCTION') == function
:
197 def getSerialMspDisplayPort(map):
198 return getSerialByFunction(map, "131072")
200 def getSerialRx(map):
201 rx
= getSerialByFunction(map, "64")
206 def writeTargetH(folder
, map):
207 file = open(folder
+ '/target.h', "w+")
210 * This file is part of INAV.
212 * INAV is free software: you can redistribute it and/or modify
213 * it under the terms of the GNU General Public License as published by
214 * the Free Software Foundation, either version 3 of the License, or
215 * (at your option) any later version.
217 * INAV is distributed in the hope that it will be useful,
218 * but WITHOUT ANY WARRANTY; without even the implied warranty of
219 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
220 * GNU General Public License for more details.
222 * You should have received a copy of the GNU General Public License
223 * along with INAV. If not, see <http://www.gnu.org/licenses/>.
225 * This target has been autgenerated by bf2inav.py
230 //#define USE_TARGET_CONFIG
232 #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
237 board_id
= ''.join(random
.choice(string
.ascii_uppercase
) for i
in range(4))
238 file.write("#define TARGET_BOARD_IDENTIFIER \"%s\"\n" % (board_id
))
239 file.write("#define USBD_PRODUCT_STRING \"%s\"\n" % (map['board_name']))
242 file.write("// Beeper\n")
243 pin
= findPinByFunction('BEEPER', map)
246 #print ("BEEPER: %s" % (pin))
247 file.write("#define USE_BEEPER\n")
248 file.write("#define BEEPER %s\n" % (pin
))
249 if 'BEEPER_INVERTED' in map['empty_defines']:
250 file.write("#define BEEPER_INVERTED\n")
254 file.write("// Leds\n")
255 pin
= findPinByFunction('LED_STRIP', map)
258 #print ("LED: %s" % (pin))
259 file.write('#define USE_LED_STRIP\n')
260 file.write("#define WS2811_PIN %s\n" % (pin
))
262 for i
in range(0, 9):
263 pin
= findPinByFunction("LED%i" % (i
), map)
265 #print ("LED%i: %s" % (i, pin))
266 file.write("#define LED%i %s\n" % (i
, pin
))
268 # Serial ports and usb
270 file.write("// UARTs\n")
271 file.write("#define USB_IO\n")
272 file.write("#define USE_VCP\n")
274 pin
= findPinByFunction('USB_DETECT', map)
276 file.write("#define USE_USB_DETECT\n")
277 file.write("#define USB_DETECT_PIN %s\n" % (pin
))
278 #file.write("#define VBUS_SENSING_ENABLED\n");
280 for i
in range(1, 9):
281 txpin
= findPinByFunction("UART%i_TX" % (i
), map)
282 rxpin
= findPinByFunction("UART%i_RX" % (i
), map)
284 #print ("UART%s" % (i))
285 file.write("#define USE_UART%i\n" % (i
))
291 file.write("#define UART%i_RX_PIN %s\n" % (i
, rxpin
))
293 file.write("#define UART%i_TX_PIN %s\n" % (i
, txpin
))
295 file.write("#define UART%i_TX_PIN %s\n" % (i
, rxpin
))
298 for i
in range(1, 9):
299 txpin
= findPinByFunction("SOFTSERIAL%i_TX" % (i
), map)
300 rxpin
= findPinByFunction("SOFTSERIAL%i_RX" % (i
), map)
302 if txpin
!= None or rxpin
!= None:
303 #print ("SOFTUART%s" % (i))
304 file.write("#define USE_SOFTSERIAL%i\n" % (idx
))
310 file.write("#define SOFTSERIAL_%i_TX_PIN %s\n" % (idx
, txpin
))
312 file.write("#define SOFTSERIAL_%i_TX_PIN %s\n" % (idx
, rxpin
))
315 file.write("#define SOFTSERIAL_%i_RX_PIN %s\n" % (idx
, rxpin
))
317 file.write("#define SOFTSERIAL_%i_RX_PIN %s\n" % (idx
, txpin
))
319 file.write("#define SERIAL_PORT_COUNT %i\n" % (serial_count
))
321 file.write("#define DEFAULT_RX_TYPE RX_TYPE_SERIAL\n")
322 file.write("#define SERIALRX_PROVIDER SERIALRX_CRSF\n")
324 # TODO: map default serial uart
325 #serial_rx = getSerialRx(map)
328 if serial_rx
!= None:
329 file.write("#define SERIALRX_UART SERIAL_PORT_USART%s\n" % (serial_rx
))
331 file.write("// SPI\n")
332 use_spi_defined
= False
333 for i
in range(1, 9):
334 sckpin
= findPinByFunction("SPI%i_SCK" % (i
), map)
335 misopin
= findPinByFunction("SPI%i_SDI" % (i
), map)
336 mosipin
= findPinByFunction("SPI%i_SDO" % (i
), map)
337 if (sckpin
or misopin
or mosipin
):
338 if (not use_spi_defined
):
339 use_spi_defined
= True
340 file.write("#define USE_SPI\n")
341 file.write("#define USE_SPI_DEVICE_%i\n" % (i
))
344 file.write("#define SPI%i_SCK_PIN %s\n" % (i
, sckpin
))
346 file.write("#define SPI%i_MISO_PIN %s\n" % (i
, misopin
))
348 file.write("#define SPI%i_MOSI_PIN %s\n" % (i
, mosipin
))
350 use_i2c_defined
= False
351 for i
in range(1, 9):
352 sclpin
= findPinByFunction("I2C%i_SCL" % (i
), map)
353 sdapin
= findPinByFunction("I2C%i_SDA" % (i
), map)
354 if (sclpin
or sdapin
):
355 if (not use_i2c_defined
):
356 file.write("// I2C\n")
358 use_i2c_defined
= True
359 file.write("#define USE_I2C\n")
360 file.write("#define USE_I2C_DEVICE_%i\n" % (i
))
363 file.write("#define I2C%i_SCL %s\n" % (i
, sclpin
))
365 file.write("#define I2C%i_SDA %s\n" % (i
, sdapin
))
367 if 'MAG_I2C_INSTANCE' in map['defines']:
368 file.write("// MAG\n")
369 bfinstance
= map['defines']['MAG_I2C_INSTANCE']
370 file.write("#define USE_MAG\n")
371 file.write("#define USE_MAG_ALL\n")
373 m
= re
.search(r
'^\s*#define\s+MAG_I2C_INSTANCE\s+\(?I2CDEV_(\d+)\)?\s*$', bfinstance
)
375 file.write("#define MAG_I2C_BUS BUS_I2C%i" % (m
.group(1)))
377 file.write("// ADC\n")
382 pin
= findPinByFunction('ADC_VBAT', map)
385 file.write("#define ADC_CHANNEL_1_PIN %s\n" % (pin
))
386 file.write("#define VBAT_ADC_CHANNEL ADC_CHN_1\n");
389 pin
= findPinByFunction('ADC_CURR', map)
392 file.write("#define ADC_CHANNEL_2_PIN %s\n" % (pin
))
393 file.write("#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2\n");
395 pin
= findPinByFunction('ADC_RSSI', map)
398 file.write("#define ADC_CHANNEL_3_PIN %s\n" % (pin
))
399 file.write("#define RSSI_ADC_CHANNEL ADC_CHN_3\n");
401 # ADC_EXT ch4 (airspeed?)
402 pin
= findPinByFunction('ADC_EXT_1', map)
405 file.write("#define ADC_CHANNEL_4_PIN %s\n" % (pin
))
406 file.write("#define AIRSPEED_ADC_CHANNEL ADC_CHN_4\n");
409 file.write("#define USE_ADC\n")
410 file.write("#define ADC_INSTANCE ADC1\n")
412 #define ADC1_DMA_STREAM DMA2_Stream4
414 file.write("// Gyro & ACC\n")
415 for supportedgyro
in ['BMI160', 'BMI270', 'ICM20689', 'ICM42605', 'MPU6000', 'MPU6500', 'MPU9250']:
417 for var
in ['USE_ACCGYRO_', 'USE_ACC_', 'USE_ACC_SPI', 'USE_GYRO_', 'USE_GYRO_SPI_']:
418 val
= var
+ supportedgyro
419 if val
in map['empty_defines']:
424 #print (supportedgyro)
425 file.write("#define USE_IMU_%s\n" % (supportedgyro
))
426 file.write("#define %s_CS_PIN %s\n" % (supportedgyro
, findPinByFunction('GYRO_1_CS', map)))
427 file.write("#define %s_SPI_BUS BUS_%s\n" % (supportedgyro
, map['defines']['GYRO_1_SPI_INSTANCE']))
428 file.write("#define IMU_%s_ALIGN %s\n" % (supportedgyro
, getGyroAlign(map)))
431 if 'USE_BARO' in map['empty_defines']:
433 file.write("// BARO\n")
434 file.write("#define USE_BARO\n")
435 if 'BARO_I2C_INSTANCE' in map['defines']:
436 file.write("#define USE_BARO_ALL\n")
437 m
= re
.search(r
'I2CDEV_(\d+)', map['defines']['BARO_I2C_INSTANCE'])
439 file.write("#define BARO_I2C_BUS BUS_I2C%s\n" % (m
.group(1)))
440 if 'BARO_SPI_INSTANCE' in map['defines']:
441 file.write("#define USE_BARO_BMP280\n")
442 file.write("#define USE_BARO_SPI_BMP280\n")
443 file.write("#define BMP280_SPI_BUS BUS_%s\n" % (map['defines']['BARO_SPI_INSTANCE']))
444 file.write("#define BMP280_CS_PIN %s\n" % (findPinByFunction('BARO_CS', map)))
446 file.write("// OSD\n")
447 if 'USE_MAX7456' in map['empty_defines']:
448 #print ("ANALOG OSD")
449 file.write("#define USE_MAX7456\n")
450 pin
= findPinByFunction('MAX7456_SPI_CS', map)
451 file.write("#define MAX7456_CS_PIN %s\n" % (pin
))
452 file.write("#define MAX7456_SPI_BUS BUS_%s\n" % (map['defines']['MAX7456_SPI_INSTANCE']))
453 file.write("// Blackbox\n")
456 if 'USE_FLASH' in map['empty_defines']:
457 #print ("FLASH BLACKBOX")
458 cs
= findPinByFunction("FLASH_CS", map)
459 spiflash_bus
= map['defines'].get('FLASH_SPI_INSTANCE')
461 # TODO: add more drivers
462 suppored_flash_chips
= [
469 file.write("#define USE_FLASHFS\n")
470 file.write("#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT\n")
471 for flash
in suppored_flash_chips
:
472 file.write("#define USE_FLASH_%s\n" % (flash
))
473 file.write("#define %s_SPI_BUS BUS_%s\n" % (flash
, spiflash_bus
))
474 file.write("#define %s_CS_PIN %s\n" % (flash
, cs
))
478 for i
in range(1, 9):
479 sdio_cmd
= findPinByFunction("SDIO_CMD_%i" % (i
), map)
483 file.write("#define USE_SDCARD\n")
484 file.write("#define USE_SDCARD_SDIO\n")
485 file.write("#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT\n")
487 file.write("#define SDCARD_SDIO_4BIT\n")
488 file.write("#define SDCARD_SDIO_DEVICE SDIODEV_%i\n" % (i
))
492 for i
in range(1, 9):
493 pinio
= findPinByFunction("PINIO%i" % (i
), map)
497 file.write("\n// PINIO\n\n")
498 file.write("#define USE_PINIO\n")
499 file.write("#define USE_PINIOBOX\n")
500 file.write("#define PINIO%i_PIN %s\n" % (i
, pinio
))
502 file.write("\n\n// Others\n\n")
504 pwm_outputs
= getPwmOutputCount(map)
505 file.write("#define MAX_PWM_OUTPUT_PORTS %i\n" % (pwm_outputs
))
506 file.write("#define USE_SERIAL_4WAY_BLHELI_INTERFACE\n")
508 file.write("#define USE_DSHOT\n")
509 file.write("#define USE_ESC_SENSOR\n")
511 if 'DEFAULT_VOLTAGE_METER_SCALE' in map['defines']:
512 file.write("#define VOLTAGE_METER_SCALE %s\n" % (map['defines']['DEFAULT_VOLTAGE_METER_SCALE']))
513 if 'DEFAULT_CURRENT_METER_SCALE' in map['defines']:
514 file.write("#define CURRENT_METER_SCALE %s\n" % (map['defines']['DEFAULT_CURRENT_METER_SCALE']))
517 port_config
= getPortConfig(map)
519 file.write(port_config
)
525 def mcu2timerKey(mcu
):
526 m
= re
.search(r
'^AT32F435[GM]', mcu
)
530 m
= re
.search(r
'^STM32F405', mcu
)
534 m
= re
.search(r
'^STM32F7[2Xx]2', mcu
)
538 m
= re
.search(r
'^STM32F7[Xx46]5', mcu
)
542 m
= re
.search(r
'^STM32H7[45]3', mcu
)
546 print ("Unsupported MCU: %s" % (mcu
))
550 def getTimerInfo(map, pin
):
551 with
open("timer_pins.yaml", "r") as f
:
552 pindb
= yaml
.safe_load(f
)
555 mcu
= map['mcu']['type']
556 tk
= mcu2timerKey(mcu
)
559 print ("PINDB not available for MCU: %s" % (mcu
))
562 timers
= pindb
[tk
].get(pin
, None)
567 timer
= list(ti
.keys())[0]
570 result
.append([timer
, channel
])
576 def writeTargetC(folder
, map):
577 file = open(folder
+ '/target.c', "w+")
580 * This file is part of INAV.
582 * INAV is free software: you can redistribute it and/or modify
583 * it under the terms of the GNU General Public License as published by
584 * the Free Software Foundation, either version 3 of the License, or
585 * (at your option) any later version.
587 * INAV is distributed in the hope that it will be useful,
588 * but WITHOUT ANY WARRANTY; without even the implied warranty of
589 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
590 * GNU General Public License for more details.
592 * You should have received a copy of the GNU General Public License
593 * along with INAV. If not, see <http://www.gnu.org/licenses/>.
595 * This target has been autgenerated by bf2inav.py
600 #include "platform.h"
602 #include "drivers/bus.h"
603 #include "drivers/io.h"
604 #include "drivers/pwm_mapping.h"
605 #include "drivers/timer.h"
606 #include "drivers/pinio.h"
607 //#include "drivers/sensor.h"
611 #for supportedgyro in ['BMI160', 'BMI270', 'ICM20689', 'ICM42605', 'MPU6000', 'MPU6500', 'MPU9250']:
613 # for var in ['USE_ACCGYRO_', 'USE_ACC_', 'USE_ACC_SPI', 'USE_GYRO_', 'USE_GYRO_SPI_']:
614 # val = var + supportedgyro
615 # if val in map['empty_defines']:
620 # file.write("//BUSDEV_REGISTER_SPI_TAG(busdev_%s, DEVHW_%s, %s_SPI_BUS, %s_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_%s_ALIGN);\n" % (supportedgyro.lower(), supportedgyro, supportedgyro, supportedgyro, supportedgyro))
623 file.write("\ntimerHardware_t timerHardware[] = {\n")
625 motors
= findPinsByFunction("MOTOR", map)
628 timerInfo
= getTimerInfo(map, motor
)
632 for (t
, ch
) in timerInfo
:
634 file.write(" DEF_TIM(%s, %s, %s, TIM_USE_OUTPUT_AUTO, 0, %s), // S%i\n" % (t
, ch
, motor
, 0, snum
))
638 file.write(" //DEF_TIM(%s, %s, %s, TIM_USE_OUTPUT_AUTO, 0, %s),\n" % (t
, ch
, motor
, 0))
641 servos
= findPinsByFunction("SERVO", map)
644 timerInfo
= getTimerInfo(map, servo
)
648 for (t
, ch
) in timerInfo
:
650 file.write(" DEF_TIM(%s, %s, %s, TIM_USE_OUTPUT_AUTO, 0, %s), // S%i\n" % (t
, ch
, servo
, 0, snum
))
654 file.write(" //DEF_TIM(%s, %s, %s, TIM_USE_OUTPUT_AUTO, 0, %s),\n" % (t
, ch
, servo
, 0))
657 beeper
= findPinByFunction("BEEPER", map)
659 timerInfo
= getTimerInfo(map, beeper
)
662 #print ("BEEPER: %s" % (timerInfo))
663 for (t
, ch
) in timerInfo
:
665 file.write(" DEF_TIM(%s, %s, %s, TIM_USE_BEEPER, 0, %s),\n" % (t
, ch
, beeper
, 0))
668 file.write(" //DEF_TIM(%s, %s, %s, TIM_USE_BEEPER, 0, %s),\n" % (t
, ch
, beeper
, 0))
671 led
= findPinByFunction("LED_STRIP", map)
673 timerInfo
= getTimerInfo(map, led
)
677 for (t
, ch
) in timerInfo
:
679 file.write(" DEF_TIM(%s, %s, %s, TIM_USE_LED, 0, %s),\n" % (t
, ch
, led
, 0))
682 file.write(" //DEF_TIM(%s, %s, %s, TIM_USE_LED, 0, %s),\n" % (t
, ch
, led
, 0))
687 const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
693 def writeConfigC(folder
, map):
694 file = open(folder
+ '/config.c', "w+")
697 * This file is part of INAV.
699 * INAV is free software: you can redistribute it and/or modify
700 * it under the terms of the GNU General Public License as published by
701 * the Free Software Foundation, either version 3 of the License, or
702 * (at your option) any later version.
704 * INAV is distributed in the hope that it will be useful,
705 * but WITHOUT ANY WARRANTY; without even the implied warranty of
706 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
707 * GNU General Public License for more details.
709 * You should have received a copy of the GNU General Public License
710 * along with INAV. If not, see <http://www.gnu.org/licenses/>.
712 * This target has been autgenerated by bf2inav.py
717 #include "platform.h"
719 #include "fc/fc_msp_box.h"
720 #include "fc/config.h"
722 #include "io/piniobox.h"
724 void targetConfiguration(void)
727 #//pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
728 #//pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
729 #//beeperConfigMutable()->pwmMode = true;
738 def writeTarget(outputFolder
, map):
739 writeCmakeLists(outputFolder
, map)
740 writeTargetH(outputFolder
, map)
741 writeTargetC(outputFolder
, map)
742 writeConfigC(outputFolder
, map)
746 def buildMap(inputFile
):
747 map = { 'defines': {}, 'empty_defines': [], 'features': ['FEATURE_OSD', 'FEATURE_TELEMETRY', 'FEATURE_CURRENT_METER', 'FEATURE_VBAT', 'FEATURE_TX_PROF_SEL', 'FEATURE_BLACKBOX'], 'pins': {}, 'funcs': {}, 'timer_pin_map': {}}
749 f
= open(inputFile
, 'r')
754 m
= re
.search(r
'^#define\s+FC_TARGET_MCU\s+([0-9A-Za-z]+)$', l
)
756 map['mcu'] = {'type': m
.group(1)}
758 m
= re
.search(r
'^#define\s+BOARD_NAME\s+(\w+)$', l
)
760 map['board_name'] = m
.group(1)
762 m
= re
.search(r
'^#define\s+MANUFACTURER_ID\s+(\w+)$', l
)
764 map['manufacturer_id'] = m
.group(1)
766 m
= re
.search(r
'^#define\s+(\w+)\s*$', l
)
768 map['empty_defines'].append(re
.sub('ICM42688P', 'ICM42605', m
.group(1)))
770 m
= re
.search(r
'^\s*#define\s+DEFAULT_FEATURES\s+\((.+?)\)\s*$', l
)
772 features
= m
.group(1).split('|')
773 for feat
in features
:
775 if not feat
in map['features']:
776 map['features'].append(feat
)
778 m
= re
.search(r
'^#define\s+(\w+)\s+(\S+)\s*$', l
)
780 map['defines'][m
.group(1)] = m
.group(2)
786 # o: timer channel? 1 = first
789 # TIMER_PIN_MAP( 0, PB8 , 2, -1) \
790 m
= re
.search(r
'^\s*TIMER_PIN_MAP\s*\(\s*(\d+)\s*,\s*([0-9A-Za-z]+)\s*,\s*(\d+)\s*,\s*(-?\d+)\s*\).+', l
)
792 map['timer_pin_map'][m
.group(1)] = {
800 m
= re
.search(r
'^\s*#define\s+(\w+)_PIN\s+([A-Z0-9]+)\s*$', l
)
804 if not map['funcs'].get(func
):
805 map['funcs'][func
] = {}
807 map['funcs'][func
] = pin
809 if not map['pins'].get(pin
):
810 map['pins'][pin
] = {}
812 map['pins'][pin
] = func
815 #m = re.search(r'^feature\s+(-?\w+)$', l)
817 # map['features'].append(m.group(1))
819 #m = re.search(r'^resource\s+(-?\w+)\s+(\d+)\s+(\w+)$', l)
821 # resource_type = m.group(1)
822 # resource_index = m.group(2)
823 # pin = translatePin(m.group(3))
824 # if not map['pins'].get(pin):
825 # map['pins'][pin] = {}
827 # map['pins'][pin]['function'] = translateFunctionName(resource_type, resource_index)
829 #m = re.search(r'^timer\s+(\w+)\s+AF(\d+)$', l)
831 # pin = translatePin(m.group(1))
832 # if not map['pins'].get(pin):
833 # map['pins'][pin] = {}
835 # map['pins'][pin]['AF'] = m.group(2)
837 #m = re.search(r'^#\s*pin\s+(\w+):\s*(TIM\d+)\s+(CH\d+).+$', l)
839 # pin = translatePin(m.group(1))
840 # if not map['pins'].get(pin):
841 # map['pins'][pin] = {}
843 # map['pins'][pin]['TIM'] = m.group(2)
844 # map['pins'][pin]['CH'] = m.group(3)
846 #m = re.search(r'^dma\s+([A-Za-z0-9]+)\s+([A-Za-z0-9]+)\s+(\d+).*$', l)
848 # if(m.group(1) == 'ADC'):
849 # pin = 'ADC' + m.group(2)
851 # pin = translatePin(m.group(2))
852 # if not map['dmas'].get(pin):
853 # map['dmas'][pin] = {}
854 # map['dmas'][pin]['DMA'] = m.group(3)
857 # pin B04: DMA1 Stream 4 Channel 5
859 #m = re.search(r'^#\s+pin\s+(\w+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Channel\s+(\d+)\s*$', l)
861 # pin = translatePin(m.group(1))
862 # if not map['pins'].get(pin):
863 # map['pins'][pin] = {}
865 # map['pins'][pin]['DMA_STREAM'] = m.group(3)
866 # map['pins'][pin]['DMA_CHANNEL'] = m.group(4)
868 #m = re.search(r'^#\s+ADC\s+(\d+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Channel\s+(\d+)\s*$', l)
870 # pin = 'ADC' + m.group(1)
871 # if not map['dmas'].get(pin):
872 # map['dmas'][pin] = {}
874 # map['dmas'][pin]['DMA_STREAM'] = m.group(3)
875 # map['dmas'][pin]['DMA_CHANNEL'] = m.group(4)
877 #m = re.search(r'^#\s+TIMUP\s+(\d+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Channel\s+(\d+)\s*$', l)
879 # pin = 'TIMUP' + m.group(1)
880 # if not map['dmas'].get(pin):
881 # map['dmas'][pin] = {}
882 # map['dmas'][pin]['DMA_STREAM'] = m.group(3)
883 # map['dmas'][pin]['DMA_CHANNEL'] = m.group(4)
885 #m = re.search(r'^#\s+ADC\s+(\d+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Request\s+(\d+)\s*$', l)
887 # pin = 'ADC' + m.group(1)
888 # if not map['dmas'].get(pin):
889 # map['dmas'][pin] = {}
891 # map['dmas'][pin]['DMA_STREAM'] = m.group(3)
892 # map['dmas'][pin]['DMA_REQUEST'] = m.group(4)
894 #m = re.search(r'^#\s+TIMUP\s+(\d+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Channel\s+(\d+)\s*$', l)
896 # pin = 'TIMUP' + m.group(1)
897 # if not map['dmas'].get(pin):
898 # map['dmas'][pin] = {}
900 # map['dmas'][pin]['DMA_STREAM'] = m.group(3)
901 # map['dmas'][pin]['DMA_CHANNEL'] = m.group(4)
903 #m = re.search(r'^#\s+TIMUP\s+(\d+):\s+(DMA\d+)\s+Stream\s+(\d+)\s+Request\s+(\d+)\s*$', l)
905 # pin = 'TIMUP' + m.group(1)
906 # if not map['dmas'].get(pin):
907 # map['dmas'][pin] = {}
908 # map['dmas'][pin]['DMA_STREAM'] = m.group(3)
909 # map['dmas'][pin]['DMA_REQUEST'] = m.group(4)
911 #m = re.search(r'^serial\s+(\d+)\s+(\d+)\s+(\d+)\s+(\d+)\s+(\d+)\s+(\d+)$', l)
914 # if not map['serial'].get(idx):
915 # map['serial'][idx] = {}
917 # map['serial'][idx]['FUNCTION'] = m.group(2)
918 # map['serial'][idx]['MSP_BAUD'] = m.group(3)
919 # map['serial'][idx]['GPS_BAUD'] = m.group(4)
920 # map['serial'][idx]['TELEMETRY_BAUD'] = m.group(5)
921 # map['serial'][idx]['BLACKBOX_BAUD'] = m.group(6)
923 #m = re.search(r'^set\s+(\w+)\s*=\s*(\w+)$', l)
925 # map['variables'][m.group(1)] = m.group(2)
931 print ("%s -i bf-target.config -o output-directory" % (sys
.argv
[0]))
932 print (" -i | --input-config=<file> -- print this help")
933 print (" -o | --output-dir=<targetdir> -- print this help")
934 print (" -h | --help -- print this help")
935 print (" -v | --version -- print version")
944 opts
, args
= getopt
.getopt(argv
,"hvi:o:", ["input-config=", "output-dir=", 'version', 'help'])
945 except getopt
.GeoptError
:
949 for opt
, arg
in opts
:
950 if opt
in ('-h', '--help'):
953 elif opt
in ('-i', '--input-config'):
955 elif opt
in ('-o', '--output-dir'):
957 elif opt
in ('-v', '--version'):
958 print ("%s: %s" % (sys
.argv
[0], version
))
961 if (not os
.path
.isfile(inputfile
) ):
962 print("no such file %s" % inputfile
)
964 if (not os
.path
.isdir(outputdir
) ):
965 print("no such directory %s" % outputdir
)
968 targetDefinition
= buildMap(inputfile
)
971 map = buildMap(inputfile
)
973 print (json
.dumps(map, indent
=4))
975 writeTarget(outputdir
, map)
980 if( __name__
== "__main__"):