mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed GPIO init for H7
This commit is contained in:
parent
9013c15f4d
commit
de335f14d7
|
@ -169,8 +169,13 @@ static void stm32_gpio_init(void) {
|
||||||
|
|
||||||
/* Enabling GPIO-related clocks, the mask comes from the
|
/* Enabling GPIO-related clocks, the mask comes from the
|
||||||
registry header file.*/
|
registry header file.*/
|
||||||
|
#if defined(STM32H7)
|
||||||
|
rccResetAHB4(STM32_GPIO_EN_MASK);
|
||||||
|
rccEnableAHB4(STM32_GPIO_EN_MASK, true);
|
||||||
|
#else
|
||||||
rccResetAHB1(STM32_GPIO_EN_MASK);
|
rccResetAHB1(STM32_GPIO_EN_MASK);
|
||||||
rccEnableAHB1(STM32_GPIO_EN_MASK, true);
|
rccEnableAHB1(STM32_GPIO_EN_MASK, true);
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Initializing all the defined GPIO ports.*/
|
/* Initializing all the defined GPIO ports.*/
|
||||||
#if STM32_HAS_GPIOA
|
#if STM32_HAS_GPIOA
|
||||||
|
|
|
@ -37,8 +37,8 @@ pincount = {
|
||||||
'G': 16,
|
'G': 16,
|
||||||
'H': 16,
|
'H': 16,
|
||||||
'I': 16,
|
'I': 16,
|
||||||
'J': 0,
|
'J': 16,
|
||||||
'K': 0
|
'K': 16
|
||||||
}
|
}
|
||||||
|
|
||||||
# no DMA map as we will dynamically allocate DMA channels using the DMAMUX
|
# no DMA map as we will dynamically allocate DMA channels using the DMAMUX
|
||||||
|
|
Loading…
Reference in New Issue