Browse Source

HAL_ChibiOS: fixed GPIO init for H7

master
Andrew Tridgell 6 years ago
parent
commit
de335f14d7
  1. 5
      libraries/AP_HAL_ChibiOS/hwdef/common/board.c
  2. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py

5
libraries/AP_HAL_ChibiOS/hwdef/common/board.c

@ -169,8 +169,13 @@ static void stm32_gpio_init(void) { @@ -169,8 +169,13 @@ static void stm32_gpio_init(void) {
/* Enabling GPIO-related clocks, the mask comes from the
registry header file.*/
#if defined(STM32H7)
rccResetAHB4(STM32_GPIO_EN_MASK);
rccEnableAHB4(STM32_GPIO_EN_MASK, true);
#else
rccResetAHB1(STM32_GPIO_EN_MASK);
rccEnableAHB1(STM32_GPIO_EN_MASK, true);
#endif
/* Initializing all the defined GPIO ports.*/
#if STM32_HAS_GPIOA

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py

@ -37,8 +37,8 @@ pincount = { @@ -37,8 +37,8 @@ pincount = {
'G': 16,
'H': 16,
'I': 16,
'J': 0,
'K': 0
'J': 16,
'K': 16
}
# no DMA map as we will dynamically allocate DMA channels using the DMAMUX

Loading…
Cancel
Save