hwdef-bl.dat 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  1. # hw definition file for processing by chibios_pins.py
  2. # MCU class and specific type
  3. MCU STM32F4xx STM32F412Rx
  4. FLASH_RESERVE_START_KB 0
  5. # two sectors for bootloader, two for storage
  6. FLASH_BOOTLOADER_LOAD_KB 64
  7. # board ID for firmware load
  8. APJ_BOARD_ID 1001
  9. # setup build for a peripheral firmware
  10. env AP_PERIPH 1
  11. # crystal frequency
  12. OSCILLATOR_HZ 16000000
  13. STM32_HSE_ENABLED TRUE
  14. STM32_PLLM_VALUE 16
  15. STM32_PLLN_VALUE 384
  16. STM32_PLLP_VALUE 4
  17. STM32_PLLQ_VALUE 8
  18. STM32_PLLSRC STM32_PLLSRC_HSE
  19. STM32_PREE1 STM32_PREE1_DIV1
  20. STM32_PREE2 STM32_PREE2_DIV1
  21. STM32_HPRE STM32_HPRE_DIV1
  22. STM32_PPRE1 STM32_PPRE1_DIV2
  23. STM32_PPRE2 STM32_PPRE2_DIV2
  24. define CH_CFG_ST_FREQUENCY 1000000
  25. # assume 512k flash part
  26. FLASH_SIZE_KB 512
  27. STDOUT_SERIAL SD1
  28. STDOUT_BAUDRATE 57600
  29. # board voltage
  30. STM32_VDD 330U
  31. # order of UARTs
  32. UART_ORDER
  33. # use safety button to stay in bootloader
  34. PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN
  35. define HAL_STAY_IN_BOOTLOADER_VALUE 1
  36. PB12 LED_BOOTLOADER OUTPUT LOW
  37. define HAL_LED_ON 1
  38. # USART1
  39. PB6 USART1_TX USART1
  40. PB7 USART1_RX USART1
  41. # USART2
  42. PA2 USART2_TX USART2
  43. PA3 USART2_RX USART2
  44. # SWD debugging
  45. PA13 JTMS-SWDIO SWD
  46. PA14 JTCK-SWCLK SWD
  47. define HAL_USE_SERIAL TRUE
  48. define STM32_SERIAL_USE_USART1 TRUE
  49. define STM32_SERIAL_USE_USART2 TRUE
  50. define STM32_SERIAL_USE_USART3 FALSE
  51. define HAL_NO_GPIO_IRQ
  52. define HAL_USE_EMPTY_IO TRUE
  53. # avoid timer and RCIN threads to save memory
  54. define HAL_NO_TIMER_THREAD
  55. define HAL_NO_RCIN_THREAD
  56. define HAL_USE_RTC FALSE
  57. define DISABLE_SERIAL_ESC_COMM TRUE
  58. define NO_DATAFLASH TRUE
  59. define DMA_RESERVE_SIZE 0
  60. define PERIPH_FW TRUE
  61. define HAL_DISABLE_LOOP_DELAY
  62. define HAL_USE_EMPTY_STORAGE 1
  63. define HAL_STORAGE_SIZE 16384
  64. # enable CAN support
  65. PB8 CAN1_RX CAN1
  66. PB9 CAN1_TX CAN1
  67. PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
  68. define HAL_USE_CAN TRUE
  69. define STM32_CAN_USE_CAN1 TRUE
  70. define CAN_APP_VERSION_MAJOR 1
  71. define CAN_APP_VERSION_MINOR 0
  72. define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
  73. # start with a fixed node ID so the board is usable without DNA
  74. define HAL_CAN_DEFAULT_NODE_ID 116
  75. # make bl baudrate match debug baudrate for easier debugging
  76. define BOOTLOADER_BAUDRATE 57600
  77. # use a small bootloader timeout
  78. define HAL_BOOTLOADER_TIMEOUT 1000