stm32: Add support for G4 MCUs, and add NUCLEO_G474RE board defn.

This commit adds support for the STM32G4 series of MCUs, and a board
definition for NUCLEO_G474RE.  This board has the REPL on LPUART1 which is
connected to the on-board ST-link USB-UART.
This commit is contained in:
Herwin Grobben 2021-01-26 14:49:56 +01:00 committed by Damien George
parent 60e05ae84e
commit 8f68e26f79
32 changed files with 1050 additions and 91 deletions

View File

@ -94,6 +94,7 @@ endif
CFLAGS_MCU_f0 = $(CFLAGS_CORTEX_M) -mtune=cortex-m0 -mcpu=cortex-m0
CFLAGS_MCU_f4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4
CFLAGS_MCU_f7 = $(CFLAGS_CORTEX_M) -mtune=cortex-m7 -mcpu=cortex-m7
CFLAGS_MCU_g4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4
CFLAGS_MCU_l0 = $(CFLAGS_CORTEX_M) -mtune=cortex-m0plus -mcpu=cortex-m0plus
CFLAGS_MCU_l4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4
CFLAGS_MCU_h7 = $(CFLAGS_CORTEX_M) -mtune=cortex-m7 -mcpu=cortex-m7
@ -429,6 +430,10 @@ $(BUILD)/$(HAL_DIR)/Src/stm32$(MCU_SERIES)xx_hal_mmc.o: CFLAGS += -Wno-error=par
endif
endif
ifeq ($(MCU_SERIES),$(filter $(MCU_SERIES),g4))
HAL_SRC_C += $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES)xx_, hal_fdcan.c)
endif
ifeq ($(CMSIS_MCU),$(filter $(CMSIS_MCU),STM32H743xx STM32H750xx STM32H7A3xx STM32H7A3xxQ STM32H7B3xx STM32H7B3xxQ))
HAL_SRC_C += $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES)xx_, hal_fdcan.c)
else

View File

@ -102,6 +102,16 @@
#define ADC_CAL2 ((uint16_t *)(ADC_CAL_ADDRESS + 4))
#define ADC_CAL_BITS (12)
#elif defined(STM32G4)
#define ADC_FIRST_GPIO_CHANNEL (0)
#define ADC_LAST_GPIO_CHANNEL (18)
#define ADC_SCALE_V (((float)VREFINT_CAL_VREF) / 1000.0f)
#define ADC_CAL_ADDRESS VREFINT_CAL_ADDR
#define ADC_CAL1 TEMPSENSOR_CAL1_ADDR
#define ADC_CAL2 TEMPSENSOR_CAL2_ADDR
#define ADC_CAL_BITS (12) // UM2570, __HAL_ADC_CALC_TEMPERATURE: 'corresponds to a resolution of 12 bits'
#elif defined(STM32H7)
#define ADC_SCALE_V (3.3f)
@ -141,6 +151,8 @@
defined(STM32F746xx) || defined(STM32F765xx) || \
defined(STM32F767xx) || defined(STM32F769xx)
#define VBAT_DIV (4)
#elif defined(STM32G4)
#define VBAT_DIV (3)
#elif defined(STM32H743xx) || defined(STM32H747xx) || \
defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || \
defined(STM32H7B3xx) || defined(STM32H7B3xxQ) || \
@ -206,7 +218,7 @@ STATIC bool is_adcx_channel(int channel) {
ADC_HandleTypeDef handle;
handle.Instance = ADCx;
return IS_ADC_CHANNEL(&handle, channel);
#elif defined(STM32WB)
#elif defined(STM32G4) || defined(STM32WB)
ADC_HandleTypeDef handle;
handle.Instance = ADCx;
return __HAL_ADC_IS_CHANNEL_INTERNAL(channel)
@ -220,7 +232,7 @@ STATIC void adc_wait_for_eoc_or_timeout(ADC_HandleTypeDef *adcHandle, int32_t ti
uint32_t tickstart = HAL_GetTick();
#if defined(STM32F4) || defined(STM32F7)
while ((adcHandle->Instance->SR & ADC_FLAG_EOC) != ADC_FLAG_EOC) {
#elif defined(STM32F0) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32F0) || defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
while (READ_BIT(adcHandle->Instance->ISR, ADC_FLAG_EOC) != ADC_FLAG_EOC) {
#else
#error Unsupported processor
@ -237,6 +249,8 @@ STATIC void adcx_clock_enable(ADC_HandleTypeDef *adch) {
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
__HAL_RCC_ADC12_CLK_ENABLE();
__HAL_RCC_ADC_CONFIG(RCC_ADCCLKSOURCE_CLKP);
#elif defined(STM32G4)
__HAL_RCC_ADC12_CLK_ENABLE();
#elif defined(STM32H7)
if (adch->Instance == ADC3) {
__HAL_RCC_ADC3_CLK_ENABLE();
@ -286,7 +300,7 @@ STATIC void adcx_init_periph(ADC_HandleTypeDef *adch, uint32_t resolution) {
adch->Init.OversamplingMode = DISABLE;
adch->Init.LeftBitShift = ADC_LEFTBITSHIFT_NONE;
adch->Init.ConversionDataManagement = ADC_CONVERSIONDATA_DR;
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
adch->Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
adch->Init.ScanConvMode = ADC_SCAN_DISABLE;
adch->Init.LowPowerAutoWait = DISABLE;
@ -303,7 +317,7 @@ STATIC void adcx_init_periph(ADC_HandleTypeDef *adch, uint32_t resolution) {
#if defined(STM32H7)
HAL_ADCEx_Calibration_Start(adch, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED);
#endif
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
HAL_ADCEx_Calibration_Start(adch, ADC_SINGLE_ENDED);
#endif
}
@ -312,7 +326,7 @@ STATIC void adc_init_single(pyb_obj_adc_t *adc_obj) {
adc_obj->handle.Instance = ADCx;
adcx_init_periph(&adc_obj->handle, ADC_RESOLUTION_12B);
#if defined(STM32L4) && defined(ADC_DUALMODE_REGSIMULT_INJECSIMULT)
#if (defined(STM32G4) || defined(STM32L4)) && defined(ADC_DUALMODE_REGSIMULT_INJECSIMULT)
ADC_MultiModeTypeDef multimode;
multimode.Mode = ADC_MODE_INDEPENDENT;
if (HAL_ADCEx_MultiModeConfigChannel(&adc_obj->handle, &multimode) != HAL_OK) {
@ -324,7 +338,7 @@ STATIC void adc_init_single(pyb_obj_adc_t *adc_obj) {
STATIC void adc_config_channel(ADC_HandleTypeDef *adc_handle, uint32_t channel) {
ADC_ChannelConfTypeDef sConfig;
#if defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32WB)
sConfig.Rank = ADC_REGULAR_RANK_1;
if (__HAL_ADC_IS_CHANNEL_INTERNAL(channel) == 0) {
channel = __HAL_ADC_DECIMAL_NB_TO_CHANNEL(channel);
@ -352,7 +366,7 @@ STATIC void adc_config_channel(ADC_HandleTypeDef *adc_handle, uint32_t channel)
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.OffsetRightShift = DISABLE;
sConfig.OffsetSignedSaturation = DISABLE;
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
if (__HAL_ADC_IS_CHANNEL_INTERNAL(channel)) {
sConfig.SamplingTime = ADC_SAMPLETIME_247CYCLES_5;
} else {
@ -536,7 +550,7 @@ STATIC mp_obj_t adc_read_timed(mp_obj_t self_in, mp_obj_t buf_in, mp_obj_t freq_
// for subsequent samples we can just set the "start sample" bit
#if defined(STM32F4) || defined(STM32F7)
self->handle.Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART;
#elif defined(STM32F0) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32F0) || defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
SET_BIT(self->handle.Instance->CR, ADC_CR_ADSTART);
#else
#error Unsupported processor
@ -646,7 +660,7 @@ STATIC mp_obj_t adc_read_timed_multi(mp_obj_t adc_array_in, mp_obj_t buf_array_i
// ADC is started: set the "start sample" bit
#if defined(STM32F4) || defined(STM32F7)
adc->handle.Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART;
#elif defined(STM32F0) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32F0) || defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
SET_BIT(adc->handle.Instance->CR, ADC_CR_ADSTART);
#else
#error Unsupported processor
@ -766,7 +780,16 @@ STATIC uint32_t adc_config_and_read_ref(ADC_HandleTypeDef *adcHandle, uint32_t c
}
int adc_read_core_temp(ADC_HandleTypeDef *adcHandle) {
#if defined(STM32G4)
int32_t raw_value = 0;
if (adcHandle->Instance == ADC1) {
raw_value = adc_config_and_read_ref(adcHandle, ADC_CHANNEL_TEMPSENSOR_ADC1);
} else {
return 0;
}
#else
int32_t raw_value = adc_config_and_read_ref(adcHandle, ADC_CHANNEL_TEMPSENSOR);
#endif
return ((raw_value - CORE_TEMP_V25) / CORE_TEMP_AVG_SLOPE) + 25;
}
@ -775,7 +798,16 @@ int adc_read_core_temp(ADC_HandleTypeDef *adcHandle) {
STATIC volatile float adc_refcor = 1.0f;
float adc_read_core_temp_float(ADC_HandleTypeDef *adcHandle) {
#if defined(STM32G4)
int32_t raw_value = 0;
if (adcHandle->Instance == ADC1) {
raw_value = adc_config_and_read_ref(adcHandle, ADC_CHANNEL_TEMPSENSOR_ADC1);
} else {
return 0;
}
#else
int32_t raw_value = adc_config_and_read_ref(adcHandle, ADC_CHANNEL_TEMPSENSOR);
#endif
float core_temp_avg_slope = (*ADC_CAL2 - *ADC_CAL1) / 80.0f;
return (((float)raw_value * adc_refcor - *ADC_CAL1) / core_temp_avg_slope) + 30.0f;
}

View File

@ -48,6 +48,8 @@ static inline void adc_deselect_vbat(ADC_TypeDef *adc, uint32_t channel) {
adc_common = ADC_COMMON_REGISTER(0);
#elif defined(STM32F7)
adc_common = ADC123_COMMON;
#elif defined(STM32G4)
adc_common = ADC12_COMMON;
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
adc_common = ADC12_COMMON;
#elif defined(STM32H7)

View File

@ -0,0 +1,15 @@
{
"deploy": [
"../deploy.md"
],
"docs": "",
"features": [],
"images": [
"nucleo_g474re.jpg"
],
"mcu": "stm32g4",
"product": "Nucleo G474RE",
"thumbnail": "",
"url": "",
"vendor": "ST Microelectronics"
}

View File

@ -0,0 +1,95 @@
#define MICROPY_HW_BOARD_NAME "NUCLEO_G474RE"
#define MICROPY_HW_MCU_NAME "STM32G474"
#define MICROPY_HW_ENABLE_RTC (1)
#define MICROPY_HW_ENABLE_RNG (1)
#define MICROPY_HW_ENABLE_ADC (1)
#define MICROPY_HW_ENABLE_DAC (1) // A4, A5
#define MICROPY_HW_ENABLE_USB (0) // A12 (dp), A11 (dm)
#define MICROPY_HW_HAS_SWITCH (1)
#define MICROPY_HW_HAS_FLASH (0) // QSPI extflash not mounted
#define MICROPY_PY_UASYNCIO (0)
#define MICROPY_PY_UZLIB (0)
#define MICROPY_PY_UBINASCII (0)
#define MICROPY_PY_UHASHLIB (0)
#define MICROPY_PY_UJSON (0)
#define MICROPY_PY_URE (0)
#define MICROPY_PY_FRAMEBUF (0)
#define MICROPY_PY_USOCKET (0)
#define MICROPY_PY_NETWORK (0)
// The board has an 24MHz HSE, the following gives 170MHz CPU speed
#define MICROPY_HW_CLK_PLLM (6)
#define MICROPY_HW_CLK_PLLN (85)
#define MICROPY_HW_CLK_PLLP (2)
#define MICROPY_HW_CLK_PLLQ (8)
#define MICROPY_HW_CLK_PLLR (2)
#define MICROPY_HW_CLK_USE_HSI48 (1) // for RNG
// 4 wait states
#define MICROPY_HW_FLASH_LATENCY FLASH_LATENCY_8
// UART config
#define MICROPY_HW_LPUART1_TX (pin_A2) // A2 (to STLINK), B11, C1
#define MICROPY_HW_LPUART1_RX (pin_A3) // A3 (to STLINK), B10, C0
#define MICROPY_HW_UART1_TX (pin_C4) // A9, B6, C4, E0
#define MICROPY_HW_UART1_RX (pin_C5) // A10, B7, C5, E1
//#define MICROPY_HW_UART2_TX (pin_A2) // A14, B3, D5
//#define MICROPY_HW_UART2_RX (pin_A3) // A15, B4, D6
//#define MICROPY_HW_UART2_RTS (pin_A1) // D4
//#define MICROPY_HW_UART2_CTS (pin_A0) // D3
#define MICROPY_HW_UART3_TX (pin_B10) // B9, B10, C10, D8
#define MICROPY_HW_UART3_RX (pin_B11) // B8 = boot0, B11, C11, D9, E15
//#define MICROPY_HW_UART3_RTS (pin_B14) // D12, F6
//#define MICROPY_HW_UART3_CTS (pin_B13) // A13, D11
//#define MICROPY_HW_UART4_TX (pin_) // C10
//#define MICROPY_HW_UART4_RX (pin_) // C11
#define MICROPY_HW_UART_REPL (PYB_LPUART_1) // default on Nucleo G474
#define MICROPY_HW_UART_REPL_BAUD (115200)
// I2C buses
#define MICROPY_HW_I2C1_SCL (pin_B8) // A13, A15, B8 (=boot0)
#define MICROPY_HW_I2C1_SDA (pin_B9) // A14, B7, B9
//#define MICROPY_HW_I2C2_SCL (pin_) // A9, C4
//#define MICROPY_HW_I2C2_SDA (pin_) // A8, F0
//#define MICROPY_HW_I2C3_SCL (pin_) // A8, C8
//#define MICROPY_HW_I2C3_SDA (pin_) // B5, C9, C11
// SPI
#define MICROPY_HW_SPI1_NSS (pin_A4) // A4, A15 (Nucleo64 specifies B6 as pin CS, must be done as GPIO, not as AF)
#define MICROPY_HW_SPI1_SCK (pin_A5) // A5 (LED), B3 (SWO)
#define MICROPY_HW_SPI1_MISO (pin_A6) // A6, B4
#define MICROPY_HW_SPI1_MOSI (pin_A7) // A7, B5
//#define MICROPY_HW_SPI2_NSS (pin_) // B12, D15, F0
//#define MICROPY_HW_SPI2_SCK (pin_) // B13, F1, F9, F10
//#define MICROPY_HW_SPI2_MISO (pin_) // A10, B14
//#define MICROPY_HW_SPI2_MOSI (pin_) // A11, B15
//#define MICROPY_HW_SPI3_NSS (pin_) // A4, A15
//#define MICROPY_HW_SPI3_SCK (pin_) // B3, C10
//#define MICROPY_HW_SPI3_MISO (pin_) // B4, C11
//#define MICROPY_HW_SPI3_MOSI (pin_) // B5, C12
// USRSW is pulled low. Pressing the button makes the input go high.
#define MICROPY_HW_USRSW_PIN (pin_C13)
#define MICROPY_HW_USRSW_PULL (GPIO_NOPULL)
#define MICROPY_HW_USRSW_EXTI_MODE (GPIO_MODE_IT_RISING)
#define MICROPY_HW_USRSW_PRESSED (1)
// LEDs
#define MICROPY_HW_LED1 (pin_A5) // green
#define MICROPY_HW_LED_ON(pin) (mp_hal_pin_high(pin))
#define MICROPY_HW_LED_OFF(pin) (mp_hal_pin_low(pin))
// USB config pin A12 (dp), A11 (dm) not mounted on Nucleo
//#define MICROPY_HW_USB_FS (1)
//#define MICROPY_HW_USB_VBUS_DETECT_PIN (pin_A9)
//#define MICROPY_HW_USB_OTG_ID_PIN (pin_A10)
// FDCAN bus
// User TODO: fit transceiver chip
#define MICROPY_HW_CAN1_NAME "FDCAN1"
#define MICROPY_HW_CAN1_TX (pin_A12) // A12, B9, D1
#define MICROPY_HW_CAN1_RX (pin_A11) // A11, B8, D0

View File

@ -0,0 +1,6 @@
# MCU settings
MCU_SERIES = g4
CMSIS_MCU = STM32G474xx
MICROPY_FLOAT_IMPL = single
AF_FILE = boards/stm32g474_af.csv
LD_FILES = boards/stm32g474.ld boards/common_basic.ld

View File

@ -0,0 +1,86 @@
A0,PA0
A1,PA1
A2,PA4
A3,BPB0
A4,PC1
A5,PC0
D0,PC5
D1,PC4
D2,PA10
D3,PB3
D4,PB5
D5,PB4
D6,PB10
D7,PA8
D8,PA9
D9,PC7
D10,PB6
D11,PA7
D12,PA6
D13,PA5
D14,PB9
D15,PB8
SW,PC13
I2C_SDA,PB9
I2C_SCL,PB8
LED1,PA5
SPI_MOSI,PA7
SPI_MISO,PA6
SPI_SCK,PA5
SPI_CS,PB6
LPUART1_TX,PA2
LPUART1_RX,PA3
UART1_TX,PC4
UART1_RX,PC5
CN7_1,PC10
CN7_2,PC11
CN7_3,PC12
CN7_4,PD2
CN7_7,PB8
CN7_13,PA13
CN7_15,PA14
CN7_17,PA15
CN7_21,PB7
CN7_23,PC13
CN7_25,PC14
CN7_27,PC15
CN7_28,PA0
CN7_29,PF0
CN7_30,PA1
CN7_31,PF1
CN7_32,PA4
CN7_34,PB0
CN7_35,PC2
CN7_36,PC1
CN7_37,PC3
CN7_38,PC0
CN10_1,PC9
CN10_2,PC8
CN10_3,PB8
CN10_4,PC6
CN10_5,PB9
CN10_6,PC5
CN10_11,PA5
CN10_12,PA12
CN10_13,PA6
CN10_14,PA11
CN10_15,PA7
CN10_16,PB12
CN10_17,PB6
CN10_18,PB11
CN10_19,PC7
CN10_21,PA9
CN10_22,PB2
CN10_23,PA8
CN10_24,PB1
CN10_25,PB10
CN10_26,PB15
CN10_27,PB4
CN10_28,PB14
CN10_29,PB5
CN10_30,PB13
CN10_31,PB3
CN10_33,PA10
CN10_34,PC4
CN10_35,PC4
CN10_37,PC5
1 A0 PA0
2 A1 PA1
3 A2 PA4
4 A3 BPB0
5 A4 PC1
6 A5 PC0
7 D0 PC5
8 D1 PC4
9 D2 PA10
10 D3 PB3
11 D4 PB5
12 D5 PB4
13 D6 PB10
14 D7 PA8
15 D8 PA9
16 D9 PC7
17 D10 PB6
18 D11 PA7
19 D12 PA6
20 D13 PA5
21 D14 PB9
22 D15 PB8
23 SW PC13
24 I2C_SDA PB9
25 I2C_SCL PB8
26 LED1 PA5
27 SPI_MOSI PA7
28 SPI_MISO PA6
29 SPI_SCK PA5
30 SPI_CS PB6
31 LPUART1_TX PA2
32 LPUART1_RX PA3
33 UART1_TX PC4
34 UART1_RX PC5
35 CN7_1 PC10
36 CN7_2 PC11
37 CN7_3 PC12
38 CN7_4 PD2
39 CN7_7 PB8
40 CN7_13 PA13
41 CN7_15 PA14
42 CN7_17 PA15
43 CN7_21 PB7
44 CN7_23 PC13
45 CN7_25 PC14
46 CN7_27 PC15
47 CN7_28 PA0
48 CN7_29 PF0
49 CN7_30 PA1
50 CN7_31 PF1
51 CN7_32 PA4
52 CN7_34 PB0
53 CN7_35 PC2
54 CN7_36 PC1
55 CN7_37 PC3
56 CN7_38 PC0
57 CN10_1 PC9
58 CN10_2 PC8
59 CN10_3 PB8
60 CN10_4 PC6
61 CN10_5 PB9
62 CN10_6 PC5
63 CN10_11 PA5
64 CN10_12 PA12
65 CN10_13 PA6
66 CN10_14 PA11
67 CN10_15 PA7
68 CN10_16 PB12
69 CN10_17 PB6
70 CN10_18 PB11
71 CN10_19 PC7
72 CN10_21 PA9
73 CN10_22 PB2
74 CN10_23 PA8
75 CN10_24 PB1
76 CN10_25 PB10
77 CN10_26 PB15
78 CN10_27 PB4
79 CN10_28 PB14
80 CN10_29 PB5
81 CN10_30 PB13
82 CN10_31 PB3
83 CN10_33 PA10
84 CN10_34 PC4
85 CN10_35 PC4
86 CN10_37 PC5

View File

@ -0,0 +1,19 @@
/* This file is part of the MicroPython project, http://micropython.org/
* The MIT License (MIT)
* Copyright (c) 2019 Damien P. George
*/
#ifndef MICROPY_INCLUDED_STM32G4XX_HAL_CONF_H
#define MICROPY_INCLUDED_STM32G4XX_HAL_CONF_H
#include "boards/stm32g4xx_hal_conf_base.h"
// Oscillator values in Hz
#define HSE_VALUE (24000000)
#define LSE_VALUE (32768)
#define EXTERNAL_CLOCK_VALUE (24000)
// Oscillator timeouts in ms
#define HSE_STARTUP_TIMEOUT (100)
#define LSE_STARTUP_TIMEOUT (5000)
#endif // MICROPY_INCLUDED_STM32G4XX_HAL_CONF_H

View File

@ -219,23 +219,24 @@ class Pin(object):
def parse_adc(self, adc_str):
if adc_str[:3] != "ADC":
return
adc, channel = None, None
if adc_str.find("_INP") != -1:
# STM32H7xx, entries have the form: ADCxx_IN[PN]yy/...
# for now just pick the entry with the most ADC periphs
adc, channel = None, None
for ss in adc_str.split("/"):
if ss.find("_INP") != -1:
a, c = ss.split("_")
if adc is None or len(a) > len(adc):
adc, channel = a, c
if adc is None:
return
channel = channel[3:]
sep = "_INP"
else:
# all other MCUs, entries have the form: ADCxx_INyy
adc, channel = adc_str.split("_")
channel = channel[2:]
sep = "_IN"
# Pick the entry with the most ADC peripherals
for ss in adc_str.split("/"):
if ss.find(sep) != -1:
a, c = ss.split("_")
if adc is None or len(a) > len(adc):
adc, channel = a, c
if adc is None:
return
channel = channel[len(sep) - 1 :]
for idx in range(3, len(adc)):
adc_num = int(adc[idx]) # 1, 2, or 3

View File

@ -0,0 +1,28 @@
/* Specify the memory areas */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 352K
FLASH_FS (rx) : ORIGIN = 0x08058000, LENGTH = 160K /* starting @ 352K */
}
/* Generate a link error if heap and stack don't fit into RAM */
_minimum_heap_size = 0x200; /* required amount of heap */
_minimum_stack_size = 0x400; /* required amount of stack */
_ram_start = ORIGIN(RAM);
_ram_end = ORIGIN(RAM) + LENGTH(RAM);
_micropy_hw_internal_flash_storage_ram_cache_end = ORIGIN(RAM) + LENGTH(RAM);
_micropy_hw_internal_flash_storage_ram_cache_start = _micropy_hw_internal_flash_storage_ram_cache_end - 2K; /* fs cache = 2K RAM */
/* Define the stack. The stack is full descending so begins just above last byte
of RAM. Note that EABI requires the stack to be 8-byte aligned for a call. */
_estack = _micropy_hw_internal_flash_storage_ram_cache_start - _estack_reserve;
_sstack = _estack - 8K; /* tunable */
_heap_start = _ebss; /* heap starts just after statically allocated memory */
_heap_end = _sstack;
_micropy_hw_internal_flash_storage_start = ORIGIN(FLASH_FS);
_micropy_hw_internal_flash_storage_end = ORIGIN(FLASH_FS) + LENGTH(FLASH_FS);

View File

@ -0,0 +1,109 @@
Port,,AF0,AF1,AF2,AF3,AF4,AF5,AF6,AF7,AF8,AF9,AF10,AF11,AF12,AF13,AF14,AF15,
,,I2C4/SYS_AF,LPTIM1/TIM2/5/15/16/17,I2C1/3/TIM1/2/3/4/5/8/20/15/COMP1,QUADSPI1/I2C3/4/SAI1/USB/HRTIM1/TIM8/20/15/COMP3,I2C1/2/3/4/TIM1/8/16/17,QUADSPI1/SPI1/2/3/4/I2S2/3/I2C4/UART4/5/TIM8/Infrared,QUADSPI1/SPI2/3/I2S2/3/TIM1/5/8/20/Infrared,USART1/2/3/CAN/COMP7/5/6,I2C3/4/UART4/5/LPUART1/COMP1/2/7/4/5/6/3,CAN/TIM1/8/15/CAN1/2,QUADSPI1/TIM2/3/4/8/17,LPTIM1/TIM1/8/CAN1/3,FMC/LPUART1/SAI1/HRTIM1/TIM1,SAI1SAI1/HRTIM1/OPAMP2,UART4/5/SAI1/TIM2/15/UCPD1,SYS,ADC,COMP,DAC,OPAMP
PortA,PA0,,TIM2_CH1,TIM5_CH1,,,,,USART2_CTS,COMP1_OUT,TIM8_BKIN,TIM8_ETR,,,,TIM2_ETR,EVENTOUT,ADC12_IN1,COMP1_INM/COMP3_INP,,
PortA,PA1,RTC_REFIN,TIM2_CH2,TIM5_CH2,,,,,USART2_RTS_DE,,TIM15_CH1N,,,,,,EVENTOUT,ADC12_IN2,COMP1_INP,,OPAMP1_VINP/OPAMP3_VINP/OPAMP6_VINM
PortA,PA2,,TIM2_CH3,TIM5_CH3,,,,,USART2_TX,COMP2_OUT,TIM15_CH1,QUADSPI1_BK1_NCS,,LPUART1_TX,,UCPD1_FRSTX,EVENTOUT,ADC1_IN3,COMP2_INM,,OPAMP1_VOUT
PortA,PA3,,TIM2_CH4,TIM5_CH4,SAI1_CK1,,,,USART2_RX,,TIM15_CH2,QUADSPI1_CLK,,LPUART1_RX,SAI1_MCLK_A,,EVENTOUT,ADC1_IN4,COMP2_INP,,OPAMP1_VINM/OPAMP1_VINP/OPAMP5_VINM
PortA,PA4,,,TIM3_CH2,,,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_CK,,,,,,SAI1_FS_B,,EVENTOUT,ADC2_IN17,COMP1_INM,DAC1_OUT1,
PortA,PA5,,TIM2_CH1,TIM2_ETR,,,SPI1_SCK,,,,,,,,,UCPD1_FRSTX,EVENTOUT,ADC2_IN13,COMP2_INM,DAC1_OUT2,OPAMP2_VINM
PortA,PA6,,TIM16_CH1,TIM3_CH1,,TIM8_BKIN,SPI1_MISO,TIM1_BKIN,,COMP1_OUT,,QUADSPI1_BK1_IO3,,LPUART1_CTS,,,EVENTOUT,ADC2_IN3,,DAC2_OUT1,OPAMP2_VOUT
PortA,PA7,,TIM17_CH1,TIM3_CH2,,TIM8_CH1N,SPI1_MOSI,TIM1_CH1N,,COMP2_OUT,,QUADSPI1_BK1_IO2,,,,UCPD1_FRSTX,EVENTOUT,ADC2_IN4,COMP2_INP,,OPAMP1_VINP/OPAMP2_VINP
PortA,PA8,MCO,,I2C3_SCL,,I2C2_SDA,I2S2_MCK,TIM1_CH1,USART1_CK,COMP7_OUT,,TIM4_ETR,CAN3_RX,SAI1_CK2,HRTIM1_CHA1,SAI1_SCK_A,EVENTOUT,ADC5_IN1,,,OPAMP5_VOUT
PortA,PA9,,,I2C3_SMBA,,I2C2_SCL,I2S3_MCK,TIM1_CH2,USART1_TX,COMP5_OUT,TIM15_BKIN,TIM2_CH3,,,HRTIM1_CHA2,SAI1_FS_A,EVENTOUT,ADC5_IN2,,,
PortA,PA10,,TIM17_BKIN,,USB_CRS_SYNC,I2C2_SMBA,SPI2_MISO,TIM1_CH3,USART1_RX,COMP6_OUT,,TIM2_CH4,TIM8_BKIN,SAI1_D1,HRTIM1_CHB1,SAI1_SD_A,EVENTOUT,,,,
PortA,PA11,,,,,,SPI2_MOSI/I2S2_SD,TIM1_CH1N,USART1_CTS,COMP1_OUT,CAN1_RX,TIM4_CH1,TIM1_CH4,TIM1_BKIN2,HRTIM1_CHB2,,EVENTOUT,,,,
PortA,PA12,,TIM16_CH1,,,,I2SCKIN,TIM1_CH2N,USART1_RTS_DE,COMP2_OUT,CAN1_TX,TIM4_CH2,TIM1_ETR,,HRTIM1_FLT1,,EVENTOUT,,,,
PortA,PA13,SWDIOJTMS,TIM16_CH1N,,I2C4_SCL,I2C1_SCL,IR_OUT,,USART3_CTS,,,TIM4_CH3,,,SAI1_SD_B,,EVENTOUT,,,,
PortA,PA14,SWCLKJTCK,LPTIM1_OUT,,I2C4_SMBA,I2C1_SDA,TIM8_CH2,TIM1_BKIN,USART2_TX,,,,,,SAI1_FS_B,,EVENTOUT,,,,
PortA,PA15,JTDI,TIM2_CH1,TIM8_CH1,,I2C1_SCL,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_RX,UART4_RTS_DE,TIM1_BKIN,,CAN3_TX,,HRTIM1_FLT2,TIM2_ETR,EVENTOUT,,,,
PortB,PB0,,,TIM3_CH3,,TIM8_CH2N,,TIM1_CH2N,,,,QUADSPI1_BK1_IO1,,,HRTIM1_FLT5,UCPD1_FRSTX,EVENTOUT,ADC3_IN12/ADC1_IN15,COMP4_INP,,OPAMP2_VINP/OPAMP3_VINP
PortB,PB1,,,TIM3_CH4,,TIM8_CH3N,,TIM1_CH3N,,COMP4_OUT,,QUADSPI1_BK1_IO0,,LPUART1_RTS_DE,HRTIM1_SCOUT,,EVENTOUT,ADC3_IN1/ADC1_IN12,COMP1_INP,,OPAMP3_VOUT/OPAMP6_VINM
PortB,PB2,RTC_OUT2,LPTIM1_OUT,TIM5_CH1,TIM20_CH1,I2C3_SMBA,,,,,,QUADSPI1_BK2_IO1,,,HRTIM1_SCIN,,EVENTOUT,ADC2_IN12,COMP4_INM,,OPAMP3_VINM
PortB,PB3,JTDOTRACESWO,TIM2_CH2,TIM4_ETR,USB_CRS_SYNC,TIM8_CH1N,SPI1_SCK,SPI3_SCK/I2S3_CK,USART2_TX,,,TIM3_ETR,CAN3_RX,HRTIM1_SCOUT,HRTIM1_EEV9,SAI1_SCK_B,EVENTOUT,,,,
PortB,PB4,JTRST,TIM16_CH1,TIM3_CH1,,TIM8_CH2N,SPI1_MISO,SPI3_MISO,USART2_RX,UART5_RTS_DE,,TIM17_BKIN,CAN3_TX,,HRTIM1_EEV7,SAI1_MCLK_B,EVENTOUT,,,,
PortB,PB5,,TIM16_BKIN,TIM3_CH2,TIM8_CH3N,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI/I2S3_SD,USART2_CK,I2C3_SDA,CAN2_RX,TIM17_CH1,LPTIM1_IN1,SAI1_SD_B,HRTIM1_EEV6,UART5_CTS,EVENTOUT,,,,
PortB,PB6,,TIM16_CH1N,TIM4_CH1,,,TIM8_CH1,TIM8_ETR,USART1_TX,COMP4_OUT,CAN2_TX,TIM8_BKIN2,LPTIM1_ETR,HRTIM1_SCIN,HRTIM1_EEV4,SAI1_FS_B,EVENTOUT,,,,
PortB,PB7,,TIM17_CH1N,TIM4_CH2,I2C4_SDA,I2C1_SDA,TIM8_BKIN,,USART1_RX,COMP3_OUT,,TIM3_CH4,LPTIM1_IN2,FMC_NL,HRTIM1_EEV3,UART4_CTS,EVENTOUT,,,,
PortB,PB8,,TIM16_CH1,TIM4_CH3,SAI1_CK1,I2C1_SCL,,,USART3_RX,COMP1_OUT,CAN1_RX,TIM8_CH2,,TIM1_BKIN,HRTIM1_EEV8,SAI1_MCLK_A,EVENTOUT,,,,
PortB,PB9,,TIM17_CH1,TIM4_CH4,SAI1_D2,I2C1_SDA,,IR_OUT,USART3_TX,COMP2_OUT,CAN1_TX,TIM8_CH3,,TIM1_CH3N,HRTIM1_EEV5,SAI1_FS_A,EVENTOUT,,,,
PortB,PB10,,TIM2_CH3,,,,,,USART3_TX,LPUART1_RX,,QUADSPI1_CLK,,TIM1_BKIN,HRTIM1_FLT3,SAI1_SCK_A,EVENTOUT,,COMP5_INM,,OPAMP3_VINM/OPAMP4_VINM
PortB,PB11,,TIM2_CH4,,,,,,USART3_RX,LPUART1_TX,,QUADSPI1_BK1_NCS,,,HRTIM1_FLT4,,EVENTOUT,ADC12_IN14,COMP6_INP,,OPAMP4_VINP/OPAMP6_VOUT
PortB,PB12,,,TIM5_ETR,,I2C2_SMBA,SPI2_NSS/I2S2_WS,TIM1_BKIN,USART3_CK,LPUART1_RTS_DE,CAN2_RX,,,,HRTIM1_CHC1,,EVENTOUT,ADC4_IN3/ADC1_IN11,COMP7_INM,,OPAMP4_VOUT/OPAMP6_VINP
PortB,PB13,,,,,,SPI2_SCK/I2S2_CK,TIM1_CH1N,USART3_CTS,LPUART1_CTS,CAN2_TX,,,,HRTIM1_CHC2,,EVENTOUT,ADC3_IN5,COMP5_INP,,OPAMP3_VINP/OPAMP4_VINP/OPAMP6_VINP
PortB,PB14,,TIM15_CH1,,,,SPI2_MISO,TIM1_CH2N,USART3_RTS_DE,COMP4_OUT,,,,,HRTIM1_CHD1,,EVENTOUT,ADC4_IN4/ADC1_IN5,COMP7_INP,,OPAMP2_VINP/OPAMP5_VINP
PortB,PB15,RTC_REFIN,TIM15_CH2,TIM15_CH1N,COMP3_OUT,TIM1_CH3N,SPI2_MOSI/I2S2_SD,,,,,,,,HRTIM1_CHD2,,EVENTOUT,ADC4_IN5/ADC2_IN15,COMP6_INM,,OPAMP5_VINM
PortC,PC0,,LPTIM1_IN1,TIM1_CH1,,,,,,LPUART1_RX,,,,,,,EVENTOUT,ADC12_IN6,COMP3_INM,
PortC,PC1,,LPTIM1_OUT,TIM1_CH2,,,,,,LPUART1_TX,,QUADSPI1_BK2_IO0,,,SAI1_SD_A,,EVENTOUT,ADC12_IN7,COMP3_INP,,
PortC,PC2,,LPTIM1_IN2,TIM1_CH3,COMP3_OUT,,,TIM20_CH2,,,,QUADSPI1_BK2_IO1,,,,,EVENTOUT,ADC12_IN8,,
PortC,PC3,,LPTIM1_ETR,TIM1_CH4,SAI1_D1,,,TIM1_BKIN2,,,,QUADSPI1_BK2_IO2,,,SAI1_SD_A,,EVENTOUT,ADC12_IN9,,,OPAMP5_VINP
PortC,PC4,,,TIM1_ETR,,I2C2_SCL,,,USART1_TX,,,QUADSPI1_BK2_IO3,,,,,EVENTOUT,ADC2_IN5,,,
PortC,PC5,,,TIM15_BKIN,SAI1_D3,,,TIM1_CH4N,USART1_RX,,,,,,HRTIM1_EEV10,,EVENTOUT,ADC2_IN11,,,OPAMP1_VINM/OPAMP2_VINM
PortC,PC6,,,TIM3_CH1,HRTIM1_EEV10,TIM8_CH1,,I2S2_MCK,COMP6_OUT,I2C4_SCL,,,,,HRTIM1_CHF1,,EVENTOUT,,,,
PortC,PC7,,,TIM3_CH2,HRTIM1_FLT5,TIM8_CH2,,I2S3_MCK,COMP5_OUT,I2C4_SDA,,,,,HRTIM1_CHF2,,EVENTOUT,,,,
PortC,PC8,,,TIM3_CH3,HRTIM1_CHE1,TIM8_CH3,,TIM20_CH3,COMP7_OUT,I2C3_SCL,,,,,,,EVENTOUT,,,,
PortC,PC9,,,TIM3_CH4,HRTIM1_CHE2,TIM8_CH4,I2SCKIN,TIM8_BKIN2,,I2C3_SDA,,,,,,,EVENTOUT,,,,
PortC,PC10,,,,,TIM8_CH1N,UART4_TX,SPI3_SCK/I2S3_CK,USART3_TX,,,,,,HRTIM1_FLT6,,EVENTOUT,,,,
PortC,PC11,,,,HRTIM1_EEV2,TIM8_CH2N,UART4_RX,SPI3_MISO,USART3_RX,I2C3_SDA,,,,,,,EVENTOUT,,,,
PortC,PC12,,TIM5_CH2,,HRTIM1_EEV1,TIM8_CH3N,UART5_TX,SPI3_MOSI/I2S3_SD,USART3_CK,,,,,,,UCPD1_FRSTX,EVENTOUT,,,,
PortC,PC13,,,TIM1_BKIN,,TIM1_CH1N,,TIM8_CH4N,,,,,,,,,EVENTOUT,,,,
PortC,PC14,,,,,,,,,,,,,,,,EVENTOUT,,,,
PortC,PC15,,,,,,,,,,,,,,,,EVENTOUT,,,,
PortD,PD0,,,,,,,TIM8_CH4N,,,CAN1_RX,,,FMC_D2,,,EVENTOUT,,,,
PortD,PD1,,,,,TIM8_CH4,,TIM8_BKIN2,,,CAN1_TX,,,FMC_D3,,,EVENTOUT,,,,
PortD,PD2,,,TIM3_ETR,,TIM8_BKIN,UART5_RX,,,,,,,,,,EVENTOUT,,,,
PortD,PD3,,,TIM2_CH1/TIM2_ETR,,,,,USART2_CTS,,,QUADSPI1_BK2_NCS,,FMC_CLK,,,EVENTOUT,,,,
PortD,PD4,,,TIM2_CH2,,,,,USART2_RTS_DE,,,QUADSPI1_BK2_IO0,,FMC_NOE,,,EVENTOUT,,,,
PortD,PD5,,,,,,,,USART2_TX,,,QUADSPI1_BK2_IO1,,FMC_NWE,,,EVENTOUT,,,,
PortD,PD6,,,TIM2_CH4,SAI1_D1,,,,USART2_RX,,,QUADSPI1_BK2_IO2,,FMC_NWAIT,SAI1_SD_A,,EVENTOUT,,,,
PortD,PD7,,,TIM2_CH3,,,,,USART2_CK,,,QUADSPI1_BK2_IO3,,FMC_NCE/FMC_NE1,,,EVENTOUT,,,,
PortD,PD8,,,,,,,,USART3_TX,,,,,FMC_D13,,,EVENTOUT,ADC4_IN12/ADC5_IN12,,,OPAMP4_VINM
PortD,PD9,,,,,,,,USART3_RX,,,,,FMC_D14,,,EVENTOUT,ADC4_IN13/ADC5_IN13,,,OPAMP6_VINP
PortD,PD10,,,,,,,,USART3_CK,,,,,FMC_D15,,,EVENTOUT,ADC345_IN7,COMP6_INM,,
PortD,PD11,,TIM5_ETR,,,I2C4_SMBA,,,USART3_CTS,,,,,FMC_A16,,,EVENTOUT,ADC345_IN8,COMP6_INP,,OPAMP4_VINP
PortD,PD12,,,TIM4_CH1,,,,,USART3_RTS_DE,,,,,FMC_A17,,,EVENTOUT,ADC345_IN9,COMP5_INP,,OPAMP5_VINP
PortD,PD13,,,TIM4_CH2,,,,,,,,,,FMC_A18,,,EVENTOUT,ADC345_IN10,COMP5_INM,,
PortD,PD14,,,TIM4_CH3,,,,,,,,,,FMC_D0,,,EVENTOUT,ADC345_IN11,COMP7_INP,,OPAMP2_VINP
PortD,PD15,,,TIM4_CH4,,,,SPI2_NSS,,,,,,FMC_D1,,,EVENTOUT,,COMP7_INM,,
PortE,PE0,,,TIM4_ETR,TIM20_CH4N,TIM16_CH1,,TIM20_ETR,USART1_TX,,CAN1_RXFD,,,FMC_NBL0,,,EVENTOUT,,,,
PortE,PE1,,,,,TIM17_CH1,,TIM20_CH4,USART1_RX,,,,,FMC_NBL1,,,EVENTOUT,,,,
PortE,PE2,TRACECK,,TIM3_CH1,SAI1_CK1,,SPI4_SCK,TIM20_CH1,,,,,,FMC_A23,SAI1_MCLK_A,,EVENTOUT,,,,
PortE,PE3,TRACED0,,TIM3_CH2,,,SPI4_NSS,TIM20_CH2,,,,,,FMC_A19,SAI1_SD_B,,EVENTOUT,,,,
PortE,PE4,TRACED1,,TIM3_CH3,SAI1_D2,,SPI4_NSS,TIM20_CH1N,,,,,,FMC_A20,SAI1_FS_A,,EVENTOUT,,,,
PortE,PE5,TRACED2,,TIM3_CH4,SAI1_CK2,,SPI4_MISO,TIM20_CH2N,,,,,,FMC_A21,SAI1_SCK_A,,EVENTOUT,,,,
PortE,PE6,TRACED3,,,SAI1_D1,,SPI4_MOSI,TIM20_CH3N,,,,,,FMC_A22,SAI1_SD_A,,EVENTOUT,,,,
PortE,PE7,,,TIM1_ETR,,,,,,,,,,FMC_D4,SAI1_SD_B,,EVENTOUT,ADC3_IN4,COMP4_INP,,
PortE,PE8,,TIM5_CH3,TIM1_CH1N,,,,,,,,,,FMC_D5,SAI1_SCK_B,,EVENTOUT,ADC345_IN6,COMP4_INM,,
PortE,PE9,,TIM5_CH4,TIM1_CH1,,,,,,,,,,FMC_D6,SAI1_FS_B,,EVENTOUT,ADC3_IN2,,,
PortE,PE10,,,TIM1_CH2N,,,,,,,,QUADSPI1_CLK,,FMC_D7,SAI1_MCLK_B,,EVENTOUT,ADC345_IN14,,,
PortE,PE11,,,TIM1_CH2,,,SPI4_NSS,,,,,QUADSPI1_BK1_NCS,,FMC_D8,,,EVENTOUT,ADC345_IN15,,,
PortE,PE12,,,TIM1_CH3N,,,SPI4_SCK,,,,,QUADSPI1_BK1_IO0,,FMC_D9,,,EVENTOUT,ADC345_IN16,,,
PortE,PE13,,,TIM1_CH3,,,SPI4_MISO,,,,,QUADSPI1_BK1_IO1,,FMC_D10,,,EVENTOUT,ADC3_IN3,,,
PortE,PE14,,,TIM1_CH4,,,SPI4_MOSI,TIM1_BKIN2,,,,QUADSPI1_BK1_IO2,,FMC_D11,,,EVENTOUT,ADC4_IN1,,,
PortE,PE15,,,TIM1_BKIN,,,,TIM1_CH4N,USART3_RX,,,QUADSPI1_BK1_IO3,,FMC_D12,,,EVENTOUT,ADC4_IN2,,,
PortF,PF0,,,,,I2C2_SDA,SPI2_NSS/I2S2_WS,TIM1_CH3N,,,,,,,,,EVENTOUT,ADC1_IN10,,,
PortF,PF1,,,,,,SPI2_SCK/I2S2_CK,,,,,,,,,,EVENTOUT,ADC2_IN10,COMP3_INM,,
PortF,PF2,,,TIM20_CH3,,I2C2_SMBA,,,,,,,,FMC_A2,,,EVENTOUT,,,,
PortF,PF3,,,TIM20_CH4,,I2C3_SCL,,,,,,,,FMC_A3,,,EVENTOUT,,,,
PortF,PF4,,,COMP1_OUT,TIM20_CH1N,I2C3_SDA,,,,,,,,FMC_A4,,,EVENTOUT,,,,
PortF,PF5,,,TIM20_CH2N,,,,,,,,,,FMC_A5,,,EVENTOUT,,,,
PortF,PF6,,TIM5_ETR,TIM4_CH4,SAI1_SD_B,I2C2_SCL,,TIM5_CH1,USART3_RTS,,,QUADSPI1_BK1_IO3,,,,,EVENTOUT,,,,
PortF,PF7,,,TIM20_BKIN,,,,TIM5_CH2,,,,QUADSPI1_BK1_IO2,,FMC_A1,SAI1_MCLK_B,,EVENTOUT,,,,
PortF,PF8,,,TIM20_BKIN2,,,,TIM5_CH3,,,,QUADSPI1_BK1_IO0,,FMC_A24,SAI1_SCK_B,,EVENTOUT,,,,
PortF,PF9,,,TIM20_BKIN,TIM15_CH1,,SPI2_SCK,TIM5_CH4,,,,QUADSPI1_BK1_IO1,,FMC_A25,SAI1_FS_B,,EVENTOUT,,,,
PortF,PF10,,,TIM20_BKIN2,TIM15_CH2,,SPI2_SCK,,,,,QUADSPI1_CLK,,FMC_A0,SAI1_D3,,EVENTOUT,,,,
PortF,PF11,,,TIM20_ETR,,,,,,,,,,FMC_NE4,,,EVENTOUT,,,,
PortF,PF12,,,TIM20_CH1,,,,,,,,,,FMC_A6,,,EVENTOUT,,,,
PortF,PF13,,,TIM20_CH2,,I2C4_SMBA,,,,,,,,FMC_A7,,,EVENTOUT,,,,
PortF,PF14,,,TIM20_CH3,,I2C4_SCL,,,,,,,,FMC_A8,,,EVENTOUT,,,,
PortF,PF15,,,TIM20_CH4,,I2C4_SDA,,,,,,,,FMC_A9,,,EVENTOUT,,,,
PortG,PG0,,,TIM20_CH1N,,,,,,,,,,FMC_A10,,,EVENTOUT,,,,
PortG,PG1,,,TIM20_CH2N,,,,,,,,,,FMC_A11,,,EVENTOUT,,,,
PortG,PG2,,,TIM20_CH3N,,,SPI1_SCK,,,,,,,FMC_A12,,,EVENTOUT,,,,
PortG,PG3,,,TIM20_BKIN,,I2C4_SCL,SPI1_MISO,TIM20_CH4N,,,,,,FMC_A13,,,EVENTOUT,,,,
PortG,PG4,,,TIM20_BKIN2,,I2C4_SDA,SPI1_MOSI,,,,,,,FMC_A14,,,EVENTOUT,,,,
PortG,PG5,,,TIM20_ETR,,,SPI1_NSS,,,LPUART1_CTS,,,,FMC_A15,,,EVENTOUT,,,,
PortG,PG6,,,TIM20_BKIN,,I2C3_SMBA,,,,LPUART1_RTS_DE,,,,FMC_INT,,,EVENTOUT,,,,
PortG,PG7,,,,SAI1_CK1,I2C3_SCL,,,,LPUART1_TX,,,,FMC_INT,SAI1_MCLK_A,,EVENTOUT,,,,
PortG,PG8,,,,,I2C3_SDA,,,,LPUART1_RX,,,,FMC_NE3,,,EVENTOUT,,,,
PortG,PG9,,,,,,,SPI3_SCK,USART1_TX,,,,,FMC_NCE/FMC_NE2,,TIM15_CH1N,EVENTOUT,,,,
PortG,PG10,MCO,,,,,,,,,,,,,,,EVENTOUT
1 Port,,AF0,AF1,AF2,AF3,AF4,AF5,AF6,AF7,AF8,AF9,AF10,AF11,AF12,AF13,AF14,AF15,
2 ,,I2C4/SYS_AF,LPTIM1/TIM2/5/15/16/17,I2C1/3/TIM1/2/3/4/5/8/20/15/COMP1,QUADSPI1/I2C3/4/SAI1/USB/HRTIM1/TIM8/20/15/COMP3,I2C1/2/3/4/TIM1/8/16/17,QUADSPI1/SPI1/2/3/4/I2S2/3/I2C4/UART4/5/TIM8/Infrared,QUADSPI1/SPI2/3/I2S2/3/TIM1/5/8/20/Infrared,USART1/2/3/CAN/COMP7/5/6,I2C3/4/UART4/5/LPUART1/COMP1/2/7/4/5/6/3,CAN/TIM1/8/15/CAN1/2,QUADSPI1/TIM2/3/4/8/17,LPTIM1/TIM1/8/CAN1/3,FMC/LPUART1/SAI1/HRTIM1/TIM1,SAI1SAI1/HRTIM1/OPAMP2,UART4/5/SAI1/TIM2/15/UCPD1,SYS,ADC,COMP,DAC,OPAMP
3 PortA,PA0,,TIM2_CH1,TIM5_CH1,,,,,USART2_CTS,COMP1_OUT,TIM8_BKIN,TIM8_ETR,,,,TIM2_ETR,EVENTOUT,ADC12_IN1,COMP1_INM/COMP3_INP,,
4 PortA,PA1,RTC_REFIN,TIM2_CH2,TIM5_CH2,,,,,USART2_RTS_DE,,TIM15_CH1N,,,,,,EVENTOUT,ADC12_IN2,COMP1_INP,,OPAMP1_VINP/OPAMP3_VINP/OPAMP6_VINM
5 PortA,PA2,,TIM2_CH3,TIM5_CH3,,,,,USART2_TX,COMP2_OUT,TIM15_CH1,QUADSPI1_BK1_NCS,,LPUART1_TX,,UCPD1_FRSTX,EVENTOUT,ADC1_IN3,COMP2_INM,,OPAMP1_VOUT
6 PortA,PA3,,TIM2_CH4,TIM5_CH4,SAI1_CK1,,,,USART2_RX,,TIM15_CH2,QUADSPI1_CLK,,LPUART1_RX,SAI1_MCLK_A,,EVENTOUT,ADC1_IN4,COMP2_INP,,OPAMP1_VINM/OPAMP1_VINP/OPAMP5_VINM
7 PortA,PA4,,,TIM3_CH2,,,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_CK,,,,,,SAI1_FS_B,,EVENTOUT,ADC2_IN17,COMP1_INM,DAC1_OUT1,
8 PortA,PA5,,TIM2_CH1,TIM2_ETR,,,SPI1_SCK,,,,,,,,,UCPD1_FRSTX,EVENTOUT,ADC2_IN13,COMP2_INM,DAC1_OUT2,OPAMP2_VINM
9 PortA,PA6,,TIM16_CH1,TIM3_CH1,,TIM8_BKIN,SPI1_MISO,TIM1_BKIN,,COMP1_OUT,,QUADSPI1_BK1_IO3,,LPUART1_CTS,,,EVENTOUT,ADC2_IN3,,DAC2_OUT1,OPAMP2_VOUT
10 PortA,PA7,,TIM17_CH1,TIM3_CH2,,TIM8_CH1N,SPI1_MOSI,TIM1_CH1N,,COMP2_OUT,,QUADSPI1_BK1_IO2,,,,UCPD1_FRSTX,EVENTOUT,ADC2_IN4,COMP2_INP,,OPAMP1_VINP/OPAMP2_VINP
11 PortA,PA8,MCO,,I2C3_SCL,,I2C2_SDA,I2S2_MCK,TIM1_CH1,USART1_CK,COMP7_OUT,,TIM4_ETR,CAN3_RX,SAI1_CK2,HRTIM1_CHA1,SAI1_SCK_A,EVENTOUT,ADC5_IN1,,,OPAMP5_VOUT
12 PortA,PA9,,,I2C3_SMBA,,I2C2_SCL,I2S3_MCK,TIM1_CH2,USART1_TX,COMP5_OUT,TIM15_BKIN,TIM2_CH3,,,HRTIM1_CHA2,SAI1_FS_A,EVENTOUT,ADC5_IN2,,,
13 PortA,PA10,,TIM17_BKIN,,USB_CRS_SYNC,I2C2_SMBA,SPI2_MISO,TIM1_CH3,USART1_RX,COMP6_OUT,,TIM2_CH4,TIM8_BKIN,SAI1_D1,HRTIM1_CHB1,SAI1_SD_A,EVENTOUT,,,,
14 PortA,PA11,,,,,,SPI2_MOSI/I2S2_SD,TIM1_CH1N,USART1_CTS,COMP1_OUT,CAN1_RX,TIM4_CH1,TIM1_CH4,TIM1_BKIN2,HRTIM1_CHB2,,EVENTOUT,,,,
15 PortA,PA12,,TIM16_CH1,,,,I2SCKIN,TIM1_CH2N,USART1_RTS_DE,COMP2_OUT,CAN1_TX,TIM4_CH2,TIM1_ETR,,HRTIM1_FLT1,,EVENTOUT,,,,
16 PortA,PA13,SWDIOJTMS,TIM16_CH1N,,I2C4_SCL,I2C1_SCL,IR_OUT,,USART3_CTS,,,TIM4_CH3,,,SAI1_SD_B,,EVENTOUT,,,,
17 PortA,PA14,SWCLKJTCK,LPTIM1_OUT,,I2C4_SMBA,I2C1_SDA,TIM8_CH2,TIM1_BKIN,USART2_TX,,,,,,SAI1_FS_B,,EVENTOUT,,,,
18 PortA,PA15,JTDI,TIM2_CH1,TIM8_CH1,,I2C1_SCL,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_RX,UART4_RTS_DE,TIM1_BKIN,,CAN3_TX,,HRTIM1_FLT2,TIM2_ETR,EVENTOUT,,,,
19 PortB,PB0,,,TIM3_CH3,,TIM8_CH2N,,TIM1_CH2N,,,,QUADSPI1_BK1_IO1,,,HRTIM1_FLT5,UCPD1_FRSTX,EVENTOUT,ADC3_IN12/ADC1_IN15,COMP4_INP,,OPAMP2_VINP/OPAMP3_VINP
20 PortB,PB1,,,TIM3_CH4,,TIM8_CH3N,,TIM1_CH3N,,COMP4_OUT,,QUADSPI1_BK1_IO0,,LPUART1_RTS_DE,HRTIM1_SCOUT,,EVENTOUT,ADC3_IN1/ADC1_IN12,COMP1_INP,,OPAMP3_VOUT/OPAMP6_VINM
21 PortB,PB2,RTC_OUT2,LPTIM1_OUT,TIM5_CH1,TIM20_CH1,I2C3_SMBA,,,,,,QUADSPI1_BK2_IO1,,,HRTIM1_SCIN,,EVENTOUT,ADC2_IN12,COMP4_INM,,OPAMP3_VINM
22 PortB,PB3,JTDOTRACESWO,TIM2_CH2,TIM4_ETR,USB_CRS_SYNC,TIM8_CH1N,SPI1_SCK,SPI3_SCK/I2S3_CK,USART2_TX,,,TIM3_ETR,CAN3_RX,HRTIM1_SCOUT,HRTIM1_EEV9,SAI1_SCK_B,EVENTOUT,,,,
23 PortB,PB4,JTRST,TIM16_CH1,TIM3_CH1,,TIM8_CH2N,SPI1_MISO,SPI3_MISO,USART2_RX,UART5_RTS_DE,,TIM17_BKIN,CAN3_TX,,HRTIM1_EEV7,SAI1_MCLK_B,EVENTOUT,,,,
24 PortB,PB5,,TIM16_BKIN,TIM3_CH2,TIM8_CH3N,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI/I2S3_SD,USART2_CK,I2C3_SDA,CAN2_RX,TIM17_CH1,LPTIM1_IN1,SAI1_SD_B,HRTIM1_EEV6,UART5_CTS,EVENTOUT,,,,
25 PortB,PB6,,TIM16_CH1N,TIM4_CH1,,,TIM8_CH1,TIM8_ETR,USART1_TX,COMP4_OUT,CAN2_TX,TIM8_BKIN2,LPTIM1_ETR,HRTIM1_SCIN,HRTIM1_EEV4,SAI1_FS_B,EVENTOUT,,,,
26 PortB,PB7,,TIM17_CH1N,TIM4_CH2,I2C4_SDA,I2C1_SDA,TIM8_BKIN,,USART1_RX,COMP3_OUT,,TIM3_CH4,LPTIM1_IN2,FMC_NL,HRTIM1_EEV3,UART4_CTS,EVENTOUT,,,,
27 PortB,PB8,,TIM16_CH1,TIM4_CH3,SAI1_CK1,I2C1_SCL,,,USART3_RX,COMP1_OUT,CAN1_RX,TIM8_CH2,,TIM1_BKIN,HRTIM1_EEV8,SAI1_MCLK_A,EVENTOUT,,,,
28 PortB,PB9,,TIM17_CH1,TIM4_CH4,SAI1_D2,I2C1_SDA,,IR_OUT,USART3_TX,COMP2_OUT,CAN1_TX,TIM8_CH3,,TIM1_CH3N,HRTIM1_EEV5,SAI1_FS_A,EVENTOUT,,,,
29 PortB,PB10,,TIM2_CH3,,,,,,USART3_TX,LPUART1_RX,,QUADSPI1_CLK,,TIM1_BKIN,HRTIM1_FLT3,SAI1_SCK_A,EVENTOUT,,COMP5_INM,,OPAMP3_VINM/OPAMP4_VINM
30 PortB,PB11,,TIM2_CH4,,,,,,USART3_RX,LPUART1_TX,,QUADSPI1_BK1_NCS,,,HRTIM1_FLT4,,EVENTOUT,ADC12_IN14,COMP6_INP,,OPAMP4_VINP/OPAMP6_VOUT
31 PortB,PB12,,,TIM5_ETR,,I2C2_SMBA,SPI2_NSS/I2S2_WS,TIM1_BKIN,USART3_CK,LPUART1_RTS_DE,CAN2_RX,,,,HRTIM1_CHC1,,EVENTOUT,ADC4_IN3/ADC1_IN11,COMP7_INM,,OPAMP4_VOUT/OPAMP6_VINP
32 PortB,PB13,,,,,,SPI2_SCK/I2S2_CK,TIM1_CH1N,USART3_CTS,LPUART1_CTS,CAN2_TX,,,,HRTIM1_CHC2,,EVENTOUT,ADC3_IN5,COMP5_INP,,OPAMP3_VINP/OPAMP4_VINP/OPAMP6_VINP
33 PortB,PB14,,TIM15_CH1,,,,SPI2_MISO,TIM1_CH2N,USART3_RTS_DE,COMP4_OUT,,,,,HRTIM1_CHD1,,EVENTOUT,ADC4_IN4/ADC1_IN5,COMP7_INP,,OPAMP2_VINP/OPAMP5_VINP
34 PortB,PB15,RTC_REFIN,TIM15_CH2,TIM15_CH1N,COMP3_OUT,TIM1_CH3N,SPI2_MOSI/I2S2_SD,,,,,,,,HRTIM1_CHD2,,EVENTOUT,ADC4_IN5/ADC2_IN15,COMP6_INM,,OPAMP5_VINM
35 PortC,PC0,,LPTIM1_IN1,TIM1_CH1,,,,,,LPUART1_RX,,,,,,,EVENTOUT,ADC12_IN6,COMP3_INM,
36 PortC,PC1,,LPTIM1_OUT,TIM1_CH2,,,,,,LPUART1_TX,,QUADSPI1_BK2_IO0,,,SAI1_SD_A,,EVENTOUT,ADC12_IN7,COMP3_INP,,
37 PortC,PC2,,LPTIM1_IN2,TIM1_CH3,COMP3_OUT,,,TIM20_CH2,,,,QUADSPI1_BK2_IO1,,,,,EVENTOUT,ADC12_IN8,,
38 PortC,PC3,,LPTIM1_ETR,TIM1_CH4,SAI1_D1,,,TIM1_BKIN2,,,,QUADSPI1_BK2_IO2,,,SAI1_SD_A,,EVENTOUT,ADC12_IN9,,,OPAMP5_VINP
39 PortC,PC4,,,TIM1_ETR,,I2C2_SCL,,,USART1_TX,,,QUADSPI1_BK2_IO3,,,,,EVENTOUT,ADC2_IN5,,,
40 PortC,PC5,,,TIM15_BKIN,SAI1_D3,,,TIM1_CH4N,USART1_RX,,,,,,HRTIM1_EEV10,,EVENTOUT,ADC2_IN11,,,OPAMP1_VINM/OPAMP2_VINM
41 PortC,PC6,,,TIM3_CH1,HRTIM1_EEV10,TIM8_CH1,,I2S2_MCK,COMP6_OUT,I2C4_SCL,,,,,HRTIM1_CHF1,,EVENTOUT,,,,
42 PortC,PC7,,,TIM3_CH2,HRTIM1_FLT5,TIM8_CH2,,I2S3_MCK,COMP5_OUT,I2C4_SDA,,,,,HRTIM1_CHF2,,EVENTOUT,,,,
43 PortC,PC8,,,TIM3_CH3,HRTIM1_CHE1,TIM8_CH3,,TIM20_CH3,COMP7_OUT,I2C3_SCL,,,,,,,EVENTOUT,,,,
44 PortC,PC9,,,TIM3_CH4,HRTIM1_CHE2,TIM8_CH4,I2SCKIN,TIM8_BKIN2,,I2C3_SDA,,,,,,,EVENTOUT,,,,
45 PortC,PC10,,,,,TIM8_CH1N,UART4_TX,SPI3_SCK/I2S3_CK,USART3_TX,,,,,,HRTIM1_FLT6,,EVENTOUT,,,,
46 PortC,PC11,,,,HRTIM1_EEV2,TIM8_CH2N,UART4_RX,SPI3_MISO,USART3_RX,I2C3_SDA,,,,,,,EVENTOUT,,,,
47 PortC,PC12,,TIM5_CH2,,HRTIM1_EEV1,TIM8_CH3N,UART5_TX,SPI3_MOSI/I2S3_SD,USART3_CK,,,,,,,UCPD1_FRSTX,EVENTOUT,,,,
48 PortC,PC13,,,TIM1_BKIN,,TIM1_CH1N,,TIM8_CH4N,,,,,,,,,EVENTOUT,,,,
49 PortC,PC14,,,,,,,,,,,,,,,,EVENTOUT,,,,
50 PortC,PC15,,,,,,,,,,,,,,,,EVENTOUT,,,,
51 PortD,PD0,,,,,,,TIM8_CH4N,,,CAN1_RX,,,FMC_D2,,,EVENTOUT,,,,
52 PortD,PD1,,,,,TIM8_CH4,,TIM8_BKIN2,,,CAN1_TX,,,FMC_D3,,,EVENTOUT,,,,
53 PortD,PD2,,,TIM3_ETR,,TIM8_BKIN,UART5_RX,,,,,,,,,,EVENTOUT,,,,
54 PortD,PD3,,,TIM2_CH1/TIM2_ETR,,,,,USART2_CTS,,,QUADSPI1_BK2_NCS,,FMC_CLK,,,EVENTOUT,,,,
55 PortD,PD4,,,TIM2_CH2,,,,,USART2_RTS_DE,,,QUADSPI1_BK2_IO0,,FMC_NOE,,,EVENTOUT,,,,
56 PortD,PD5,,,,,,,,USART2_TX,,,QUADSPI1_BK2_IO1,,FMC_NWE,,,EVENTOUT,,,,
57 PortD,PD6,,,TIM2_CH4,SAI1_D1,,,,USART2_RX,,,QUADSPI1_BK2_IO2,,FMC_NWAIT,SAI1_SD_A,,EVENTOUT,,,,
58 PortD,PD7,,,TIM2_CH3,,,,,USART2_CK,,,QUADSPI1_BK2_IO3,,FMC_NCE/FMC_NE1,,,EVENTOUT,,,,
59 PortD,PD8,,,,,,,,USART3_TX,,,,,FMC_D13,,,EVENTOUT,ADC4_IN12/ADC5_IN12,,,OPAMP4_VINM
60 PortD,PD9,,,,,,,,USART3_RX,,,,,FMC_D14,,,EVENTOUT,ADC4_IN13/ADC5_IN13,,,OPAMP6_VINP
61 PortD,PD10,,,,,,,,USART3_CK,,,,,FMC_D15,,,EVENTOUT,ADC345_IN7,COMP6_INM,,
62 PortD,PD11,,TIM5_ETR,,,I2C4_SMBA,,,USART3_CTS,,,,,FMC_A16,,,EVENTOUT,ADC345_IN8,COMP6_INP,,OPAMP4_VINP
63 PortD,PD12,,,TIM4_CH1,,,,,USART3_RTS_DE,,,,,FMC_A17,,,EVENTOUT,ADC345_IN9,COMP5_INP,,OPAMP5_VINP
64 PortD,PD13,,,TIM4_CH2,,,,,,,,,,FMC_A18,,,EVENTOUT,ADC345_IN10,COMP5_INM,,
65 PortD,PD14,,,TIM4_CH3,,,,,,,,,,FMC_D0,,,EVENTOUT,ADC345_IN11,COMP7_INP,,OPAMP2_VINP
66 PortD,PD15,,,TIM4_CH4,,,,SPI2_NSS,,,,,,FMC_D1,,,EVENTOUT,,COMP7_INM,,
67 PortE,PE0,,,TIM4_ETR,TIM20_CH4N,TIM16_CH1,,TIM20_ETR,USART1_TX,,CAN1_RXFD,,,FMC_NBL0,,,EVENTOUT,,,,
68 PortE,PE1,,,,,TIM17_CH1,,TIM20_CH4,USART1_RX,,,,,FMC_NBL1,,,EVENTOUT,,,,
69 PortE,PE2,TRACECK,,TIM3_CH1,SAI1_CK1,,SPI4_SCK,TIM20_CH1,,,,,,FMC_A23,SAI1_MCLK_A,,EVENTOUT,,,,
70 PortE,PE3,TRACED0,,TIM3_CH2,,,SPI4_NSS,TIM20_CH2,,,,,,FMC_A19,SAI1_SD_B,,EVENTOUT,,,,
71 PortE,PE4,TRACED1,,TIM3_CH3,SAI1_D2,,SPI4_NSS,TIM20_CH1N,,,,,,FMC_A20,SAI1_FS_A,,EVENTOUT,,,,
72 PortE,PE5,TRACED2,,TIM3_CH4,SAI1_CK2,,SPI4_MISO,TIM20_CH2N,,,,,,FMC_A21,SAI1_SCK_A,,EVENTOUT,,,,
73 PortE,PE6,TRACED3,,,SAI1_D1,,SPI4_MOSI,TIM20_CH3N,,,,,,FMC_A22,SAI1_SD_A,,EVENTOUT,,,,
74 PortE,PE7,,,TIM1_ETR,,,,,,,,,,FMC_D4,SAI1_SD_B,,EVENTOUT,ADC3_IN4,COMP4_INP,,
75 PortE,PE8,,TIM5_CH3,TIM1_CH1N,,,,,,,,,,FMC_D5,SAI1_SCK_B,,EVENTOUT,ADC345_IN6,COMP4_INM,,
76 PortE,PE9,,TIM5_CH4,TIM1_CH1,,,,,,,,,,FMC_D6,SAI1_FS_B,,EVENTOUT,ADC3_IN2,,,
77 PortE,PE10,,,TIM1_CH2N,,,,,,,,QUADSPI1_CLK,,FMC_D7,SAI1_MCLK_B,,EVENTOUT,ADC345_IN14,,,
78 PortE,PE11,,,TIM1_CH2,,,SPI4_NSS,,,,,QUADSPI1_BK1_NCS,,FMC_D8,,,EVENTOUT,ADC345_IN15,,,
79 PortE,PE12,,,TIM1_CH3N,,,SPI4_SCK,,,,,QUADSPI1_BK1_IO0,,FMC_D9,,,EVENTOUT,ADC345_IN16,,,
80 PortE,PE13,,,TIM1_CH3,,,SPI4_MISO,,,,,QUADSPI1_BK1_IO1,,FMC_D10,,,EVENTOUT,ADC3_IN3,,,
81 PortE,PE14,,,TIM1_CH4,,,SPI4_MOSI,TIM1_BKIN2,,,,QUADSPI1_BK1_IO2,,FMC_D11,,,EVENTOUT,ADC4_IN1,,,
82 PortE,PE15,,,TIM1_BKIN,,,,TIM1_CH4N,USART3_RX,,,QUADSPI1_BK1_IO3,,FMC_D12,,,EVENTOUT,ADC4_IN2,,,
83 PortF,PF0,,,,,I2C2_SDA,SPI2_NSS/I2S2_WS,TIM1_CH3N,,,,,,,,,EVENTOUT,ADC1_IN10,,,
84 PortF,PF1,,,,,,SPI2_SCK/I2S2_CK,,,,,,,,,,EVENTOUT,ADC2_IN10,COMP3_INM,,
85 PortF,PF2,,,TIM20_CH3,,I2C2_SMBA,,,,,,,,FMC_A2,,,EVENTOUT,,,,
86 PortF,PF3,,,TIM20_CH4,,I2C3_SCL,,,,,,,,FMC_A3,,,EVENTOUT,,,,
87 PortF,PF4,,,COMP1_OUT,TIM20_CH1N,I2C3_SDA,,,,,,,,FMC_A4,,,EVENTOUT,,,,
88 PortF,PF5,,,TIM20_CH2N,,,,,,,,,,FMC_A5,,,EVENTOUT,,,,
89 PortF,PF6,,TIM5_ETR,TIM4_CH4,SAI1_SD_B,I2C2_SCL,,TIM5_CH1,USART3_RTS,,,QUADSPI1_BK1_IO3,,,,,EVENTOUT,,,,
90 PortF,PF7,,,TIM20_BKIN,,,,TIM5_CH2,,,,QUADSPI1_BK1_IO2,,FMC_A1,SAI1_MCLK_B,,EVENTOUT,,,,
91 PortF,PF8,,,TIM20_BKIN2,,,,TIM5_CH3,,,,QUADSPI1_BK1_IO0,,FMC_A24,SAI1_SCK_B,,EVENTOUT,,,,
92 PortF,PF9,,,TIM20_BKIN,TIM15_CH1,,SPI2_SCK,TIM5_CH4,,,,QUADSPI1_BK1_IO1,,FMC_A25,SAI1_FS_B,,EVENTOUT,,,,
93 PortF,PF10,,,TIM20_BKIN2,TIM15_CH2,,SPI2_SCK,,,,,QUADSPI1_CLK,,FMC_A0,SAI1_D3,,EVENTOUT,,,,
94 PortF,PF11,,,TIM20_ETR,,,,,,,,,,FMC_NE4,,,EVENTOUT,,,,
95 PortF,PF12,,,TIM20_CH1,,,,,,,,,,FMC_A6,,,EVENTOUT,,,,
96 PortF,PF13,,,TIM20_CH2,,I2C4_SMBA,,,,,,,,FMC_A7,,,EVENTOUT,,,,
97 PortF,PF14,,,TIM20_CH3,,I2C4_SCL,,,,,,,,FMC_A8,,,EVENTOUT,,,,
98 PortF,PF15,,,TIM20_CH4,,I2C4_SDA,,,,,,,,FMC_A9,,,EVENTOUT,,,,
99 PortG,PG0,,,TIM20_CH1N,,,,,,,,,,FMC_A10,,,EVENTOUT,,,,
100 PortG,PG1,,,TIM20_CH2N,,,,,,,,,,FMC_A11,,,EVENTOUT,,,,
101 PortG,PG2,,,TIM20_CH3N,,,SPI1_SCK,,,,,,,FMC_A12,,,EVENTOUT,,,,
102 PortG,PG3,,,TIM20_BKIN,,I2C4_SCL,SPI1_MISO,TIM20_CH4N,,,,,,FMC_A13,,,EVENTOUT,,,,
103 PortG,PG4,,,TIM20_BKIN2,,I2C4_SDA,SPI1_MOSI,,,,,,,FMC_A14,,,EVENTOUT,,,,
104 PortG,PG5,,,TIM20_ETR,,,SPI1_NSS,,,LPUART1_CTS,,,,FMC_A15,,,EVENTOUT,,,,
105 PortG,PG6,,,TIM20_BKIN,,I2C3_SMBA,,,,LPUART1_RTS_DE,,,,FMC_INT,,,EVENTOUT,,,,
106 PortG,PG7,,,,SAI1_CK1,I2C3_SCL,,,,LPUART1_TX,,,,FMC_INT,SAI1_MCLK_A,,EVENTOUT,,,,
107 PortG,PG8,,,,,I2C3_SDA,,,,LPUART1_RX,,,,FMC_NE3,,,EVENTOUT,,,,
108 PortG,PG9,,,,,,,SPI3_SCK,USART1_TX,,,,,FMC_NCE/FMC_NE2,,TIM15_CH1N,EVENTOUT,,,,
109 PortG,PG10,MCO,,,,,,,,,,,,,,,EVENTOUT

View File

@ -0,0 +1,131 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_STM32G4XX_HAL_CONF_BASE_H
#define MICROPY_INCLUDED_STM32G4XX_HAL_CONF_BASE_H
// Include various HAL modules for convenience
#include "stm32g4xx_hal_rcc.h"
#include "stm32g4xx_hal_gpio.h"
#include "stm32g4xx_hal_dma.h"
#include "stm32g4xx_hal_cortex.h"
#include "stm32g4xx_hal_adc.h"
#include "stm32g4xx_hal_comp.h"
#include "stm32g4xx_hal_cordic.h"
#include "stm32g4xx_hal_crc.h"
#include "stm32g4xx_hal_cryp.h"
#include "stm32g4xx_hal_dac.h"
#include "stm32g4xx_hal_exti.h"
#include "stm32g4xx_hal_fdcan.h"
#include "stm32g4xx_hal_flash.h"
#include "stm32g4xx_hal_fmac.h"
#include "stm32g4xx_hal_hrtim.h"
#include "stm32g4xx_hal_irda.h"
#include "stm32g4xx_hal_iwdg.h"
#include "stm32g4xx_hal_i2c.h"
#include "stm32g4xx_hal_i2s.h"
#include "stm32g4xx_hal_lptim.h"
#include "stm32g4xx_hal_nand.h"
#include "stm32g4xx_hal_nor.h"
#include "stm32g4xx_hal_opamp.h"
#include "stm32g4xx_hal_pcd.h"
#include "stm32g4xx_hal_pwr.h"
#include "stm32g4xx_hal_qspi.h"
#include "stm32g4xx_hal_rng.h"
#include "stm32g4xx_hal_rtc.h"
#include "stm32g4xx_hal_sai.h"
#include "stm32g4xx_hal_smartcard.h"
#include "stm32g4xx_hal_smbus.h"
#include "stm32g4xx_hal_spi.h"
#include "stm32g4xx_hal_sram.h"
#include "stm32g4xx_hal_tim.h"
#include "stm32g4xx_hal_uart.h"
#include "stm32g4xx_hal_usart.h"
#include "stm32g4xx_hal_wwdg.h"
#include "stm32g4xx_ll_adc.h"
#include "stm32g4xx_ll_rtc.h"
#include "stm32g4xx_ll_usart.h"
#include "stm32g4xx_ll_lpuart.h"
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_COMP_MODULE_ENABLED
#define HAL_CORDIC_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_CRYP_MODULE_ENABLED
#define HAL_DAC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_FDCAN_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_FMAC_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_HRTIM_MODULE_ENABLED
#define HAL_IRDA_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2S_MODULE_ENABLED
#define HAL_LPTIM_MODULE_ENABLED
#define HAL_NAND_MODULE_ENABLED
#define HAL_NOR_MODULE_ENABLED
#define HAL_OPAMP_MODULE_ENABLED
#define HAL_PCD_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_QSPI_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RNG_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
#define HAL_SAI_MODULE_ENABLED
#define HAL_SMARTCARD_MODULE_ENABLED
#define HAL_SMBUS_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_SRAM_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_WWDG_MODULE_ENABLED
// Oscillator values in Hz
#define HSI_VALUE (16000000)
#define HSI48_VALUE (48000000)
#define LSI_VALUE (32000)
// SysTick priority
#define TICK_INT_PRIORITY (0x0F)
// Miscellaneous HAL settings
#define USE_RTOS 0
#define PREFETCH_ENABLE 0
#define INSTRUCTION_CACHE_ENABLE 1
#define DATA_CACHE_ENABLE 1
#define USE_SPI_CRC 1
// HAL parameter assertions are disabled
#define assert_param(expr) ((void)0)
#endif // MICROPY_INCLUDED_STM32G4XX_HAL_CONF_BASE_H

View File

@ -101,7 +101,7 @@ STATIC uint32_t TIMx_Config(mp_obj_t timer) {
} else if (tim->Instance == TIM4) {
return DAC_TRIGGER_T4_TRGO;
#endif
#if defined(TIM5)
#if defined(TIM5) && defined(DAC_TRIGGER_T5_TRGO) // G474 doesn't have this
} else if (tim->Instance == TIM5) {
return DAC_TRIGGER_T5_TRGO;
#endif
@ -124,7 +124,7 @@ STATIC uint32_t TIMx_Config(mp_obj_t timer) {
STATIC void dac_deinit(uint32_t dac_channel) {
DAC->CR &= ~(DAC_CR_EN1 << dac_channel);
#if defined(STM32H7) || defined(STM32L4)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L4)
DAC->MCR = (DAC->MCR & ~(DAC_MCR_MODE1_Msk << dac_channel)) | (DAC_OUTPUTBUFFER_DISABLE << dac_channel);
#else
DAC->CR |= DAC_CR_BOFF1 << dac_channel;
@ -142,7 +142,7 @@ STATIC void dac_config_channel(uint32_t dac_channel, uint32_t trig, uint32_t out
DAC->CR &= ~(DAC_CR_EN1 << dac_channel);
uint32_t cr_off = DAC_CR_DMAEN1 | DAC_CR_MAMP1 | DAC_CR_WAVE1 | DAC_CR_TSEL1 | DAC_CR_TEN1;
uint32_t cr_on = trig;
#if defined(STM32H7) || defined(STM32L4)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L4)
DAC->MCR = (DAC->MCR & ~(DAC_MCR_MODE1_Msk << dac_channel)) | (outbuf << dac_channel);
#else
cr_off |= DAC_CR_BOFF1;
@ -259,7 +259,7 @@ STATIC mp_obj_t pyb_dac_init_helper(pyb_dac_obj_t *self, size_t n_args, const mp
__DAC_CLK_ENABLE();
#elif defined(STM32H7)
__HAL_RCC_DAC12_CLK_ENABLE();
#elif defined(STM32F0) || defined(STM32L4)
#elif defined(STM32F0) || defined(STM32G4) || defined(STM32L4)
__HAL_RCC_DAC1_CLK_ENABLE();
#else
#error Unsupported Processor

View File

@ -74,7 +74,7 @@ typedef union {
struct _dma_descr_t {
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
DMA_Stream_TypeDef *instance;
#elif defined(STM32F0) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32F0) || defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
DMA_Channel_TypeDef *instance;
#else
#error "Unsupported Processor"
@ -89,7 +89,7 @@ struct _dma_descr_t {
static const DMA_InitTypeDef dma_init_struct_spi_i2c = {
#if defined(STM32F4) || defined(STM32F7)
.Channel = 0,
#elif defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
.Request = 0,
#endif
.Direction = 0,
@ -137,7 +137,7 @@ static const DMA_InitTypeDef dma_init_struct_i2s = {
static const DMA_InitTypeDef dma_init_struct_sdio = {
#if defined(STM32F4) || defined(STM32F7)
.Channel = 0,
#elif defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
.Request = 0,
#endif
.Direction = 0,
@ -147,7 +147,7 @@ static const DMA_InitTypeDef dma_init_struct_sdio = {
.MemDataAlignment = DMA_MDATAALIGN_WORD,
#if defined(STM32F4) || defined(STM32F7)
.Mode = DMA_PFCTRL,
#elif defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
.Mode = DMA_NORMAL,
#endif
.Priority = DMA_PRIORITY_VERY_HIGH,
@ -165,7 +165,7 @@ static const DMA_InitTypeDef dma_init_struct_sdio = {
static const DMA_InitTypeDef dma_init_struct_dac = {
#if defined(STM32F4) || defined(STM32F7)
.Channel = 0,
#elif defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
.Request = 0,
#endif
.Direction = 0,
@ -501,6 +501,86 @@ static const uint8_t dma_irqn[NSTREAM] = {
DMA2_Channel7_IRQn,
};
#elif defined(STM32G4)
#define NCONTROLLERS (2)
#if defined(STM32G431xx) || defined(STM32G441xx)
#define NSTREAMS_PER_CONTROLLER (6) // Cat 2 devices = 6, Cat 3 = 8
#else
#define NSTREAMS_PER_CONTROLLER (8) // Cat 2 devices = 6, Cat 3 = 8
#endif
#define NSTREAM (NCONTROLLERS * NSTREAMS_PER_CONTROLLER)
#define DMA_SUB_INSTANCE_AS_UINT8(dma_request) (dma_request)
#if defined(STM32G431xx) || defined(STM32G441xx)
#define DMA1_ENABLE_MASK (0x004f) // Bits in dma_enable_mask corresponding to DMA1
#define DMA2_ENABLE_MASK (0x0fc0) // Bits in dma_enable_mask corresponding to DMA2
#else
#define DMA1_ENABLE_MASK (0x00Ff) // Bits in dma_enable_mask corresponding to DMA1
#define DMA2_ENABLE_MASK (0xff00) // Bits in dma_enable_mask corresponding to DMA2
#endif
// These descriptors are ordered by DMAx_Channel number, and within a channel by request
// number. The duplicate streams are ok as long as they aren't used at the same time.
// DMA1 streams
const dma_descr_t dma_SPI_1_RX = { DMA1_Channel1, DMA_REQUEST_SPI1_RX, dma_id_0, &dma_init_struct_spi_i2c };
const dma_descr_t dma_SPI_1_TX = { DMA1_Channel2, DMA_REQUEST_SPI1_TX, dma_id_1, &dma_init_struct_spi_i2c };
const dma_descr_t dma_SPI_2_RX = { DMA1_Channel1, DMA_REQUEST_SPI2_RX, dma_id_0, &dma_init_struct_spi_i2c };
const dma_descr_t dma_SPI_2_TX = { DMA1_Channel2, DMA_REQUEST_SPI2_TX, dma_id_1, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_1_RX = { DMA1_Channel3, DMA_REQUEST_I2C1_RX, dma_id_2, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_1_TX = { DMA1_Channel4, DMA_REQUEST_I2C1_TX, dma_id_3, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_2_RX = { DMA1_Channel3, DMA_REQUEST_I2C2_RX, dma_id_2, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_2_TX = { DMA1_Channel4, DMA_REQUEST_I2C2_TX, dma_id_3, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_3_RX = { DMA1_Channel3, DMA_REQUEST_I2C3_RX, dma_id_2, &dma_init_struct_spi_i2c };
const dma_descr_t dma_I2C_3_TX = { DMA1_Channel4, DMA_REQUEST_I2C3_TX, dma_id_3, &dma_init_struct_spi_i2c };
const dma_descr_t dma_UART_3_RX = { DMA1_Channel3, DMA_REQUEST_USART3_RX, dma_id_2, &dma_init_struct_spi_i2c };
const dma_descr_t dma_UART_3_TX = { DMA1_Channel4, DMA_REQUEST_USART3_TX, dma_id_3, &dma_init_struct_spi_i2c };
#if MICROPY_HW_ENABLE_DAC
const dma_descr_t dma_DAC_1_TX = { DMA1_Channel5, DMA_REQUEST_DAC1_CHANNEL1, dma_id_4, &dma_init_struct_dac };
const dma_descr_t dma_DAC_2_TX = { DMA1_Channel6, DMA_REQUEST_DAC1_CHANNEL2, dma_id_5, &dma_init_struct_dac };
#endif
#if !defined(STM32G431xx) && !defined(STM32G441xx)
// channel 7 & 8
#endif
// DMA2 streams
const dma_descr_t dma_UART_1_RX = { DMA2_Channel1, DMA_REQUEST_USART1_RX, dma_id_6, &dma_init_struct_spi_i2c };
const dma_descr_t dma_UART_1_TX = { DMA2_Channel2, DMA_REQUEST_USART1_TX, dma_id_7, &dma_init_struct_spi_i2c };
const dma_descr_t dma_LPUART_1_RX = { DMA2_Channel3, DMA_REQUEST_LPUART1_RX, dma_id_8, &dma_init_struct_spi_i2c };
const dma_descr_t dma_LPUART_1_TX = { DMA2_Channel4, DMA_REQUEST_LPUART1_TX, dma_id_9, &dma_init_struct_spi_i2c };
const dma_descr_t dma_ADC_1 = { DMA2_Channel5, DMA_REQUEST_ADC1, dma_id_10, NULL };
const dma_descr_t dma_MEM_2_MEM = { DMA2_Channel6, DMA_REQUEST_MEM2MEM, dma_id_11, NULL };
#if !defined(STM32G431xx) && !defined(STM32G441xx)
// channel 7 & 8
#endif
static const uint8_t dma_irqn[NSTREAM] = {
DMA1_Channel1_IRQn,
DMA1_Channel2_IRQn,
DMA1_Channel3_IRQn,
DMA1_Channel4_IRQn,
DMA1_Channel5_IRQn,
DMA1_Channel6_IRQn,
#if !defined(STM32G431xx) && !defined(STM32G441xx)
DMA1_Channel7_IRQn,
DMA1_Channel8_IRQn,
#endif
DMA2_Channel1_IRQn,
DMA2_Channel2_IRQn,
DMA2_Channel3_IRQn,
DMA2_Channel4_IRQn,
DMA2_Channel5_IRQn,
DMA2_Channel6_IRQn,
#if !defined(STM32G431xx) && !defined(STM32G441xx)
DMA2_Channel7_IRQn,
DMA2_Channel8_IRQn,
#endif
};
#elif defined(STM32H7)
#define NCONTROLLERS (2)
@ -742,6 +822,125 @@ void DMA2_Stream7_IRQHandler(void) {
IRQ_EXIT(DMA2_Stream7_IRQn);
}
#elif defined(STM32G4)
void DMA1_Channel1_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel1_IRQn);
if (dma_handle[dma_id_0] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_0]);
}
IRQ_EXIT(DMA1_Channel1_IRQn);
}
void DMA1_Channel2_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel2_IRQn);
if (dma_handle[dma_id_1] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_1]);
}
IRQ_EXIT(DMA1_Channel2_IRQn);
}
void DMA1_Channel3_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel3_IRQn);
if (dma_handle[dma_id_2] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_2]);
}
IRQ_EXIT(DMA1_Channel3_IRQn);
}
void DMA1_Channel4_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel4_IRQn);
if (dma_handle[dma_id_3] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_3]);
}
IRQ_EXIT(DMA1_Channel4_IRQn);
}
void DMA1_Channel5_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel5_IRQn);
if (dma_handle[dma_id_4] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_4]);
}
IRQ_EXIT(DMA1_Channel5_IRQn);
}
void DMA1_Channel6_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel6_IRQn);
if (dma_handle[dma_id_5] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_5]);
}
IRQ_EXIT(DMA1_Channel6_IRQn);
}
#if !(defined(STM32G431xx) || defined(STM32G441xx))
void DMA1_Channel7_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel7_IRQn);
if (dma_handle[dma_id_12] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_12]);
}
IRQ_EXIT(DMA1_Channel7_IRQn);
}
void DMA1_Channel8_IRQHandler(void) {
IRQ_ENTER(DMA1_Channel8_IRQn);
if (dma_handle[dma_id_13] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_13]);
}
IRQ_EXIT(DMA1_Channel8_IRQn);
}
#endif
void DMA2_Channel1_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel1_IRQn);
if (dma_handle[dma_id_6] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_6]);
}
IRQ_EXIT(DMA2_Channel1_IRQn);
}
void DMA2_Channel2_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel2_IRQn);
if (dma_handle[dma_id_7] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_7]);
}
IRQ_EXIT(DMA2_Channel2_IRQn);
}
void DMA2_Channel3_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel3_IRQn);
if (dma_handle[dma_id_8] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_8]);
}
IRQ_EXIT(DMA2_Channel3_IRQn);
}
void DMA2_Channel4_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel4_IRQn);
if (dma_handle[dma_id_9] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_9]);
}
IRQ_EXIT(DMA2_Channel4_IRQn);
}
void DMA2_Channel5_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel5_IRQn);
if (dma_handle[dma_id_10] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_10]);
}
IRQ_EXIT(DMA2_Channel5_IRQn);
}
void DMA2_Channel6_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel6_IRQn);
if (dma_handle[dma_id_11] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_11]);
}
IRQ_EXIT(DMA2_Channel6_IRQn);
}
#if !(defined(STM32G431xx) || defined(STM32G441xx))
void DMA2_Channel7_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel7_IRQn);
if (dma_handle[dma_id_14] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_14]);
}
IRQ_EXIT(DMA2_Channel7_IRQn);
}
void DMA2_Channel8_IRQHandler(void) {
IRQ_ENTER(DMA2_Channel8_IRQn);
if (dma_handle[dma_id_15] != NULL) {
HAL_DMA_IRQHandler(dma_handle[dma_id_15]);
}
IRQ_EXIT(DMA2_Channel8_IRQn);
}
#endif
#elif defined(STM32L0)
void DMA1_Channel1_IRQHandler(void) {
@ -909,6 +1108,9 @@ static void dma_enable_clock(dma_id_t dma_id) {
if (dma_id < NSTREAMS_PER_CONTROLLER) {
if (((old_enable_mask & DMA1_ENABLE_MASK) == 0) && !DMA1_IS_CLK_ENABLED()) {
__HAL_RCC_DMA1_CLK_ENABLE();
#if defined(STM32G4)
__HAL_RCC_DMAMUX1_CLK_ENABLE();
#endif
// We just turned on the clock. This means that anything stored
// in dma_last_channel (for DMA1) needs to be invalidated.
@ -923,6 +1125,9 @@ static void dma_enable_clock(dma_id_t dma_id) {
if (((old_enable_mask & DMA2_ENABLE_MASK) == 0) && !DMA2_IS_CLK_ENABLED()) {
__HAL_RCC_DMA2_CLK_ENABLE();
#if defined(STM32G4)
__HAL_RCC_DMAMUX1_CLK_ENABLE();
#endif
// We just turned on the clock. This means that anything stored
// in dma_last_channel (for DMA2) needs to be invalidated.
@ -947,7 +1152,7 @@ void dma_init_handle(DMA_HandleTypeDef *dma, const dma_descr_t *dma_descr, uint3
dma->Instance = dma_descr->instance;
dma->Init = *dma_descr->init;
dma->Init.Direction = dir;
#if defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
dma->Init.Request = dma_descr->sub_instance;
#else
#if !defined(STM32F0)
@ -974,7 +1179,7 @@ void dma_init(DMA_HandleTypeDef *dma, const dma_descr_t *dma_descr, uint32_t dir
dma_enable_clock(dma_id);
#if defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
// Always reset and configure the H7 and L0/L4 DMA peripheral
// (dma->State is set to HAL_DMA_STATE_RESET by memset above)
// TODO: understand how L0/L4 DMA works so this is not needed
@ -1070,10 +1275,23 @@ static void dma_idle_handler(uint32_t tick) {
dma_idle.counter[controller] = 0;
if (controller == 0) {
__HAL_RCC_DMA1_CLK_DISABLE();
#if defined(STM32G4)
#if defined(DMA2)
if (__HAL_RCC_DMA2_IS_CLK_DISABLED())
#endif
{
__HAL_RCC_DMAMUX1_CLK_DISABLE();
}
#endif
}
#if defined(DMA2)
else {
__HAL_RCC_DMA2_CLK_DISABLE();
#if defined(STM32G4)
if (__HAL_RCC_DMA1_IS_CLK_DISABLED()) {
__HAL_RCC_DMAMUX1_CLK_DISABLE();
}
#endif
}
#endif
} else {
@ -1085,7 +1303,7 @@ static void dma_idle_handler(uint32_t tick) {
}
}
#if defined(STM32F0) || defined(STM32L0) || defined(STM32L4)
#if defined(STM32F0) || defined(STM32G4) || defined(STM32L0) || defined(STM32L4)
void dma_nohal_init(const dma_descr_t *descr, uint32_t config) {
DMA_Channel_TypeDef *dma = descr->instance;
@ -1108,6 +1326,9 @@ void dma_nohal_init(const dma_descr_t *descr, uint32_t config) {
} else {
__HAL_DMA2_REMAP(descr->sub_instance);
}
#elif defined(STM32G4)
uint32_t *dmamux_ctrl = (void *)(DMAMUX1_Channel0_BASE + 0x04 * descr->id);
*dmamux_ctrl = (*dmamux_ctrl & ~(0x7f)) | descr->sub_instance;
#else
DMA_Request_TypeDef *dma_ctrl = (void *)(((uint32_t)dma & ~0xff) + (DMA1_CSELR_BASE - DMA1_BASE)); // DMA1_CSELR or DMA2_CSELR
uint32_t channel_number = (((uint32_t)dma & 0xff) - 0x08) / 20; // 0 through 6

View File

@ -62,6 +62,29 @@ extern const dma_descr_t dma_I2S_1_TX;
extern const dma_descr_t dma_I2S_2_RX;
extern const dma_descr_t dma_I2S_2_TX;
#elif defined(STM32G4)
extern const dma_descr_t dma_SPI_1_RX;
extern const dma_descr_t dma_SPI_1_TX;
extern const dma_descr_t dma_SPI_2_RX;
extern const dma_descr_t dma_SPI_2_TX;
extern const dma_descr_t dma_I2C_1_RX;
extern const dma_descr_t dma_I2C_1_TX;
extern const dma_descr_t dma_I2C_2_RX;
extern const dma_descr_t dma_I2C_2_TX;
extern const dma_descr_t dma_I2C_3_RX;
extern const dma_descr_t dma_I2C_3_TX;
extern const dma_descr_t dma_UART_3_RX;
extern const dma_descr_t dma_UART_3_TX;
extern const dma_descr_t dma_DAC_1_TX;
extern const dma_descr_t dma_DAC_2_TX;
extern const dma_descr_t dma_UART_1_RX;
extern const dma_descr_t dma_UART_1_TX;
extern const dma_descr_t dma_LPUART_1_RX;
extern const dma_descr_t dma_LPUART_1_TX;
extern const dma_descr_t dma_ADC_1;
extern const dma_descr_t dma_MEM_2_MEM;
#elif defined(STM32L0)
extern const dma_descr_t dma_SPI_1_RX;

View File

@ -91,7 +91,7 @@
#define EXTI_SWIER_BB(line) (*(__IO uint32_t *)(PERIPH_BB_BASE + ((EXTI_OFFSET + offsetof(EXTI_TypeDef, SWIER)) * 32) + ((line) * 4)))
#endif
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
// The L4 MCU supports 40 Events/IRQs lines of the type configurable and direct.
// Here we only support configurable line types. Details, see page 330 of RM0351, Rev 1.
// The USB_FS_WAKUP event is a direct type and there is no support for it.
@ -138,6 +138,10 @@ STATIC mp_obj_t pyb_extint_callback_arg[EXTI_NUM_VECTORS];
#define OTG_FS_WKUP_IRQn 42 // Some MCUs don't have FS IRQ, but we want a value to put in our table
#endif
#if defined(STM32G4)
#define TAMP_STAMP_IRQn RTC_TAMP_LSECSS_IRQn
#endif
STATIC const uint8_t nvic_irq_channel[EXTI_NUM_VECTORS] = {
#if defined(STM32F0) || defined(STM32L0)
@ -178,7 +182,7 @@ STATIC const uint8_t nvic_irq_channel[EXTI_NUM_VECTORS] = {
TAMP_STAMP_LSECSS_IRQn,
RTC_WKUP_IRQn,
#else
#if defined(STM32L4)
#if defined(STM32G4) || defined(STM32L4)
PVD_PVM_IRQn,
#else
PVD_IRQn,
@ -381,7 +385,7 @@ void extint_enable(uint line) {
if (pyb_extint_mode[line] == EXTI_Mode_Interrupt) {
#if defined(STM32H7)
EXTI_D1->IMR1 |= (1 << line);
#elif defined(STM32WB)
#elif defined(STM32G4) || defined(STM32WB)
EXTI->IMR1 |= (1 << line);
#else
EXTI->IMR |= (1 << line);
@ -389,7 +393,7 @@ void extint_enable(uint line) {
} else {
#if defined(STM32H7)
EXTI_D1->EMR1 |= (1 << line);
#elif defined(STM32WB)
#elif defined(STM32G4) || defined(STM32WB)
EXTI->EMR1 |= (1 << line);
#else
EXTI->EMR |= (1 << line);
@ -415,7 +419,7 @@ void extint_disable(uint line) {
#if defined(STM32H7)
EXTI_D1->IMR1 &= ~(1 << line);
EXTI_D1->EMR1 &= ~(1 << line);
#elif defined(STM32WB)
#elif defined(STM32G4) || defined(STM32WB)
EXTI->IMR1 &= ~(1 << line);
EXTI->EMR1 &= ~(1 << line);
#else
@ -437,7 +441,7 @@ void extint_swint(uint line) {
return;
}
// we need 0 to 1 transition to trigger the interrupt
#if defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
EXTI->SWIER1 &= ~(1 << line);
EXTI->SWIER1 |= (1 << line);
#else
@ -515,7 +519,7 @@ STATIC MP_DEFINE_CONST_FUN_OBJ_1(extint_obj_swint_obj, extint_obj_swint);
/// \classmethod regs()
/// Dump the values of the EXTI registers.
STATIC mp_obj_t extint_regs(void) {
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
printf("EXTI_IMR1 %08x\n", (unsigned int)EXTI->IMR1);
printf("EXTI_IMR2 %08x\n", (unsigned int)EXTI->IMR2);
printf("EXTI_EMR1 %08x\n", (unsigned int)EXTI->EMR1);

View File

@ -43,7 +43,7 @@
#endif
#define EXTI_ETH_WAKEUP (19)
#define EXTI_USB_OTG_HS_WAKEUP (20)
#if defined(STM32F0) || defined(STM32L4)
#if defined(STM32F0) || defined(STM32G4) || defined(STM32L4)
#define EXTI_RTC_TIMESTAMP (19)
#define EXTI_RTC_WAKEUP (20)
#elif defined(STM32H7) || defined(STM32WB)

View File

@ -97,7 +97,7 @@ static const flash_layout_t flash_layout[] = {
};
#endif
#elif defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
static const flash_layout_t flash_layout[] = {
{ (uint32_t)FLASH_BASE, (uint32_t)FLASH_PAGE_SIZE, 512 },
@ -126,12 +126,20 @@ static uint32_t get_bank(uint32_t addr) {
if (addr < (FLASH_BASE + FLASH_BANK_SIZE)) {
return FLASH_BANK_1;
} else {
#if defined(FLASH_OPTR_DBANK)
return FLASH_BANK_2;
#else
return 0;
#endif
}
} else {
// bank swap
if (addr < (FLASH_BASE + FLASH_BANK_SIZE)) {
#if defined(FLASH_OPTR_DBANK)
return FLASH_BANK_2;
#else
return 0;
#endif
} else {
return FLASH_BANK_1;
}
@ -157,6 +165,25 @@ static uint32_t get_page(uint32_t addr) {
return (addr - FLASH_BASE) / FLASH_PAGE_SIZE;
}
#elif defined(STM32G4)
static uint32_t get_page(uint32_t addr) {
return (addr - FLASH_BASE) / FLASH_PAGE_SIZE;
}
static uint32_t get_bank(uint32_t addr) {
// no bank swap
if (addr < (FLASH_BASE + FLASH_BANK_SIZE)) {
return FLASH_BANK_1;
} else {
#if defined(FLASH_OPTR_DBANK)
return FLASH_BANK_2;
#else
return 0;
#endif
}
}
#endif
bool flash_is_valid_addr(uint32_t addr) {
@ -225,6 +252,12 @@ int flash_erase(uint32_t flash_dest, uint32_t num_word32) {
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
EraseInitStruct.PageAddress = flash_dest;
EraseInitStruct.NbPages = (4 * num_word32 + FLASH_PAGE_SIZE - 4) / FLASH_PAGE_SIZE;
#elif defined(STM32G4)
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS);
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
EraseInitStruct.Page = get_page(flash_dest);
EraseInitStruct.Banks = get_bank(flash_dest);
EraseInitStruct.NbPages = (4 * num_word32 + FLASH_PAGE_SIZE - 4) / FLASH_PAGE_SIZE;
#elif defined(STM32L0)
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR);
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
@ -258,7 +291,7 @@ int flash_erase(uint32_t flash_dest, uint32_t num_word32) {
#else
EraseInitStruct.VoltageRange = 0; // unused parameter on STM32H7A3/B3
#endif
#if defined(STM32H7)
#if defined(STM32G4) || defined(STM32H7)
EraseInitStruct.Banks = get_bank(flash_dest);
#endif
EraseInitStruct.Sector = flash_get_sector_info(flash_dest, NULL, NULL);
@ -337,7 +370,7 @@ int flash_write(uint32_t flash_dest, const uint32_t *src, uint32_t num_word32) {
HAL_StatusTypeDef status = HAL_OK;
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
// program the flash uint64 by uint64
for (int i = 0; i < num_word32 / 2; i++) {

View File

@ -28,7 +28,7 @@
#include "py/mphal.h"
#include "adc.h"
#if defined(STM32F0) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#if defined(STM32F0) || defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#define ADC_V2 (1)
#else
#define ADC_V2 (0)
@ -45,6 +45,8 @@
#if defined(STM32F0) || defined(STM32L0)
#define ADC_STAB_DELAY_US (1)
#define ADC_TEMPSENSOR_DELAY_US (10)
#elif defined(STM32G4)
#define ADC_STAB_DELAY_US (1) // TODO: Check if this is enough
#elif defined(STM32L4)
#define ADC_STAB_DELAY_US (10)
#elif defined(STM32WB)
@ -57,6 +59,9 @@
#elif defined(STM32F4) || defined(STM32F7)
#define ADC_SAMPLETIME_DEFAULT ADC_SAMPLETIME_15CYCLES
#define ADC_SAMPLETIME_DEFAULT_INT ADC_SAMPLETIME_480CYCLES
#elif defined(STM32G4)
#define ADC_SAMPLETIME_DEFAULT ADC_SAMPLETIME_12CYCLES_5
#define ADC_SAMPLETIME_DEFAULT_INT ADC_SAMPLETIME_247CYCLES_5
#elif defined(STM32H7)
#define ADC_SAMPLETIME_DEFAULT ADC_SAMPLETIME_8CYCLES_5
#define ADC_SAMPLETIME_DEFAULT_INT ADC_SAMPLETIME_387CYCLES_5
@ -105,7 +110,7 @@ void adc_config(ADC_TypeDef *adc, uint32_t bits) {
__HAL_RCC_ADC_CLK_ENABLE();
#else
if (adc == ADC1) {
#if defined(STM32H7)
#if defined(STM32G4) || defined(STM32H7)
__HAL_RCC_ADC12_CLK_ENABLE();
#else
__HAL_RCC_ADC1_CLK_ENABLE();
@ -113,7 +118,7 @@ void adc_config(ADC_TypeDef *adc, uint32_t bits) {
}
#if defined(ADC2)
if (adc == ADC2) {
#if defined(STM32H7)
#if defined(STM32G4) || defined(STM32H7)
__HAL_RCC_ADC12_CLK_ENABLE();
#else
__HAL_RCC_ADC2_CLK_ENABLE();
@ -122,7 +127,11 @@ void adc_config(ADC_TypeDef *adc, uint32_t bits) {
#endif
#if defined(ADC3)
if (adc == ADC3) {
#if defined(ADC345_COMMON)
__HAL_RCC_ADC345_CLK_ENABLE();
#else
__HAL_RCC_ADC3_CLK_ENABLE();
#endif
}
#endif
#endif
@ -165,7 +174,7 @@ void adc_config(ADC_TypeDef *adc, uint32_t bits) {
// ADC isn't enabled so calibrate it now
#if defined(STM32F0) || defined(STM32L0)
LL_ADC_StartCalibration(adc);
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
LL_ADC_StartCalibration(adc, LL_ADC_SINGLE_ENDED);
#else
LL_ADC_StartCalibration(adc, LL_ADC_CALIB_OFFSET_LINEARITY, LL_ADC_SINGLE_ENDED);
@ -230,7 +239,7 @@ STATIC int adc_get_bits(ADC_TypeDef *adc) {
uint32_t res = (adc->CFGR1 & ADC_CFGR1_RES) >> ADC_CFGR1_RES_Pos;
#elif defined(STM32F4) || defined(STM32F7)
uint32_t res = (adc->CR1 & ADC_CR1_RES) >> ADC_CR1_RES_Pos;
#elif defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
uint32_t res = (adc->CFGR & ADC_CFGR_RES) >> ADC_CFGR_RES_Pos;
#endif
return adc_cr_to_bits_table[res];
@ -403,7 +412,11 @@ STATIC mp_obj_t machine_adc_make_new(const mp_obj_type_t *type, size_t n_args, s
adc = ADC1;
channel = mp_obj_get_int(source);
if (channel == ADC_CHANNEL_VREFINT
#if defined(STM32G4)
|| channel == ADC_CHANNEL_TEMPSENSOR_ADC1
#else
|| channel == ADC_CHANNEL_TEMPSENSOR
#endif
#if defined(ADC_CHANNEL_VBAT)
|| channel == ADC_CHANNEL_VBAT
#endif
@ -455,7 +468,11 @@ STATIC const mp_rom_map_elem_t machine_adc_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_VREF), MP_ROM_INT(ADC_CHANNEL_VREF) },
{ MP_ROM_QSTR(MP_QSTR_CORE_VREF), MP_ROM_INT(ADC_CHANNEL_VREFINT) },
#if defined(STM32G4)
{ MP_ROM_QSTR(MP_QSTR_CORE_TEMP), MP_ROM_INT(ADC_CHANNEL_TEMPSENSOR_ADC1) },
#else
{ MP_ROM_QSTR(MP_QSTR_CORE_TEMP), MP_ROM_INT(ADC_CHANNEL_TEMPSENSOR) },
#endif
#if defined(ADC_CHANNEL_VBAT)
{ MP_ROM_QSTR(MP_QSTR_CORE_VBAT), MP_ROM_INT(ADC_CHANNEL_VBAT) },
#endif

View File

@ -459,7 +459,7 @@ STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_uart_readchar_obj, pyb_uart_readchar);
// uart.sendbreak()
STATIC mp_obj_t pyb_uart_sendbreak(mp_obj_t self_in) {
pyb_uart_obj_t *self = MP_OBJ_TO_PTR(self_in);
#if defined(STM32F0) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32F0) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
self->uartx->RQR = USART_RQR_SBKRQ; // write-only register
#else
self->uartx->CR1 |= USART_CR1_SBK;

View File

@ -63,7 +63,7 @@
#define RCC_CSR_BORRSTF RCC_CSR_PORRSTF
#endif
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
// L4 does not have a POR, so use BOR instead
#define RCC_CSR_PORRSTF RCC_CSR_BORRSTF
#endif

View File

@ -319,6 +319,16 @@
#define MICROPY_HW_MAX_UART (8)
#define MICROPY_HW_MAX_LPUART (0)
// Configuration for STM32G4 series
#elif defined(STM32G4)
#define MP_HAL_UNIQUE_ID_ADDRESS (UID_BASE)
#define PYB_EXTI_NUM_VECTORS (42) // up to 42 event/interrupt requests: 28 configurable lines, 14 direct lines
#define MICROPY_HW_MAX_I2C (3)
#define MICROPY_HW_MAX_TIMER (20) // TIM1-8, 20
#define MICROPY_HW_MAX_UART (5) // UART1-5 + LPUART1
#define MICROPY_HW_MAX_LPUART (1)
// Configuration for STM32H7A3/B3 series
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || \
defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
@ -410,7 +420,12 @@
#else
// Use HSE as a clock source (bypass or oscillator)
#define MICROPY_HW_CLK_VALUE (HSE_VALUE)
#if defined(STM32G4)
// enable HSI48 to run RNG on this clock
#define MICROPY_HW_RCC_OSCILLATOR_TYPE (RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI48)
#else
#define MICROPY_HW_RCC_OSCILLATOR_TYPE (RCC_OSCILLATORTYPE_HSE)
#endif
#define MICROPY_HW_RCC_PLL_SRC (RCC_PLLSOURCE_HSE)
#define MICROPY_HW_RCC_CR_HSxON (RCC_CR_HSEON)
#define MICROPY_HW_RCC_HSI_STATE (RCC_HSI_OFF)
@ -480,7 +495,7 @@
// Enable CAN if there are any peripherals defined
#if defined(MICROPY_HW_CAN1_TX) || defined(MICROPY_HW_CAN2_TX) || defined(MICROPY_HW_CAN3_TX)
#define MICROPY_HW_ENABLE_CAN (1)
#if defined(STM32H7)
#if defined(STM32G4) || defined(STM32H7)
#define MICROPY_HW_ENABLE_FDCAN (1) // define for MCUs with FDCAN
#endif
#else

View File

@ -99,7 +99,7 @@ void mp_hal_gpio_clock_enable(GPIO_TypeDef *gpio) {
#elif defined(STM32L0)
#define AHBxENR IOPENR
#define AHBxENR_GPIOAEN_Pos RCC_IOPENR_IOPAEN_Pos
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
#define AHBxENR AHB2ENR
#define AHBxENR_GPIOAEN_Pos RCC_AHB2ENR_GPIOAEN_Pos
#endif

View File

@ -121,8 +121,8 @@ enum {
#define I2S2 SPI2
#define I2S3 SPI3
#if defined(STM32H7)
// Make H7 FDCAN more like CAN
#if defined(STM32G4) || defined(STM32H7)
// Make G4/H7 FDCAN more like CAN
#define CAN1 FDCAN1
#define CAN2 FDCAN2
#define GPIO_AF9_CAN1 GPIO_AF9_FDCAN1

View File

@ -143,7 +143,7 @@ void powerctrl_check_enter_bootloader(void) {
if (BL_STATE_GET_KEY(bl_state) == BL_STATE_KEY && (RCC->RCC_SR & RCC_SR_SFTRSTF)) {
// Reset by NVIC_SystemReset with bootloader data set -> branch to bootloader
RCC->RCC_SR = RCC_SR_RMVF;
#if defined(STM32F0) || defined(STM32F4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
#if defined(STM32F0) || defined(STM32F4) || defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32WB)
__HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH();
#endif
branch_to_bootloader(BL_STATE_GET_REG(bl_state), BL_STATE_GET_ADDR(bl_state));
@ -378,7 +378,7 @@ STATIC uint32_t calc_apb2_div(uint32_t wanted_div) {
#endif
}
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7)
int powerctrl_set_sysclk(uint32_t sysclk, uint32_t ahb, uint32_t apb1, uint32_t apb2) {
// Return straightaway if the clocks are already at the desired frequency
@ -686,7 +686,7 @@ void powerctrl_enter_stop_mode(void) {
__HAL_RCC_WAKEUPSTOP_CLK_CONFIG(RCC_STOP_WAKEUPCLOCK_MSI);
#endif
#if !defined(STM32F0) && !defined(STM32L0) && !defined(STM32L4) && !defined(STM32WB)
#if !defined(STM32F0) && !defined(STM32G4) && !defined(STM32L0) && !defined(STM32L4) && !defined(STM32WB)
// takes longer to wake but reduces stop current
HAL_PWREx_EnableFlashPowerDown();
#endif
@ -861,6 +861,9 @@ void powerctrl_enter_standby_mode(void) {
#if defined(STM32F0) || defined(STM32L0)
#define CR_BITS (RTC_CR_ALRAIE | RTC_CR_WUTIE | RTC_CR_TSIE)
#define ISR_BITS (RTC_ISR_ALRAF | RTC_ISR_WUTF | RTC_ISR_TSF)
#elif defined(STM32G4)
#define CR_BITS (RTC_CR_ALRAIE | RTC_CR_ALRBIE | RTC_CR_WUTIE | RTC_CR_TSIE)
#define ISR_BITS (RTC_MISR_ALRAMF | RTC_MISR_ALRBMF | RTC_MISR_WUTMF | RTC_MISR_TSMF)
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
#define CR_BITS (RTC_CR_ALRAIE | RTC_CR_ALRBIE | RTC_CR_WUTIE | RTC_CR_TSIE)
#define SR_BITS (RTC_SR_ALRAF | RTC_SR_ALRBF | RTC_SR_WUTF | RTC_SR_TSF)
@ -882,6 +885,8 @@ void powerctrl_enter_standby_mode(void) {
// clear RTC wake-up flags
#if defined(SR_BITS)
RTC->SR &= ~SR_BITS;
#elif defined(STM32G4)
RTC->MISR &= ~ISR_BITS;
#else
RTC->ISR &= ~ISR_BITS;
#endif
@ -898,7 +903,7 @@ void powerctrl_enter_standby_mode(void) {
#elif defined(STM32H7)
EXTI_D1->PR1 = 0x3fffff;
PWR->WKUPCR |= PWR_WAKEUP_FLAG1 | PWR_WAKEUP_FLAG2 | PWR_WAKEUP_FLAG3 | PWR_WAKEUP_FLAG4 | PWR_WAKEUP_FLAG5 | PWR_WAKEUP_FLAG6;
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
// clear all wake-up flags
PWR->SCR |= PWR_SCR_CWUF5 | PWR_SCR_CWUF4 | PWR_SCR_CWUF3 | PWR_SCR_CWUF2 | PWR_SCR_CWUF1;
// TODO

View File

@ -130,7 +130,7 @@ const pyb_i2c_obj_t pyb_i2c_obj[] = {
#endif
};
#if defined(STM32F7) || defined(STM32L4) || defined(STM32H7)
#if defined(STM32F7) || defined(STM32G4) || defined(STM32L4) || defined(STM32H7)
// The STM32F0, F3, F7, H7 and L4 use a TIMINGR register rather than ClockSpeed and
// DutyCycle.
@ -163,6 +163,28 @@ const pyb_i2c_obj_t pyb_i2c_obj[] = {
#define MICROPY_HW_I2C_BAUDRATE_DEFAULT (PYB_I2C_SPEED_FULL)
#define MICROPY_HW_I2C_BAUDRATE_MAX (PYB_I2C_SPEED_FAST)
#elif defined(STM32G4)
// timing input depends on PLL
// for now: 170MHz sysclock, PCLK 10.625 MHz
// using PCLOCK
// generated using CubeMX
#if defined(STM32G431xx) || defined(STM32G441xx)
#define MICROPY_HW_I2C_BAUDRATE_TIMING { \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
}
#else
#define MICROPY_HW_I2C_BAUDRATE_TIMING { \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
{PYB_I2C_SPEED_STANDARD, 0x30A0A7FB}, \
}
#endif
#define MICROPY_HW_I2C_BAUDRATE_DEFAULT (PYB_I2C_SPEED_STANDARD)
#define MICROPY_HW_I2C_BAUDRATE_MAX (PYB_I2C_SPEED_STANDARD)
#elif defined(STM32H7)
// I2C TIMINGs obtained from the STHAL examples.

View File

@ -220,7 +220,7 @@ void rtc_init_finalise() {
// fresh reset; configure RTC Calendar
RTC_CalendarConfig();
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
if (__HAL_RCC_GET_FLAG(RCC_FLAG_BORRST) != RESET) {
#else
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) {
@ -261,7 +261,7 @@ STATIC HAL_StatusTypeDef PYB_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct
HAL_PWR_EnableBkUpAccess();
uint32_t tickstart = HAL_GetTick();
#if defined(STM32F7) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32F7) || defined(STM32G4) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
// __HAL_RCC_PWR_CLK_ENABLE();
// Enable write access to Backup domain
// PWR->CR1 |= PWR_CR1_DBP;
@ -339,7 +339,7 @@ STATIC HAL_StatusTypeDef PYB_RTC_Init(RTC_HandleTypeDef *hrtc) {
hrtc->Instance->PRER |= (uint32_t)(hrtc->Init.AsynchPrediv << 16);
// Exit Initialization mode
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
#if defined(STM32G4) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
hrtc->Instance->ICSR &= (uint32_t) ~RTC_ICSR_INIT;
#else
hrtc->Instance->ISR &= (uint32_t) ~RTC_ISR_INIT;
@ -353,6 +353,9 @@ STATIC HAL_StatusTypeDef PYB_RTC_Init(RTC_HandleTypeDef *hrtc) {
#elif defined(STM32F7)
hrtc->Instance->OR &= (uint32_t) ~RTC_OR_ALARMTYPE;
hrtc->Instance->OR |= (uint32_t)(hrtc->Init.OutPutType);
#elif defined(STM32G4)
hrtc->Instance->CR &= (uint32_t) ~RTC_CR_TAMPALRM_TYPE_Msk;
hrtc->Instance->CR |= (uint32_t)(hrtc->Init.OutPutType);
#else
hrtc->Instance->TAFCR &= (uint32_t) ~RTC_TAFCR_ALARMOUTTYPE;
hrtc->Instance->TAFCR |= (uint32_t)(hrtc->Init.OutPutType);
@ -699,7 +702,7 @@ mp_obj_t pyb_rtc_wakeup(size_t n_args, const mp_obj_t *args) {
RTC->CR &= ~RTC_CR_WUTE;
// wait until WUTWF is set
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
#if defined(STM32G4) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
while (!(RTC->ICSR & RTC_ICSR_WUTWF)) {
}
#else
@ -720,7 +723,7 @@ mp_obj_t pyb_rtc_wakeup(size_t n_args, const mp_obj_t *args) {
RTC->WPR = 0xff;
// enable external interrupts on line EXTI_RTC_WAKEUP
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
EXTI->IMR1 |= 1 << EXTI_RTC_WAKEUP;
EXTI->RTSR1 |= 1 << EXTI_RTC_WAKEUP;
#elif defined(STM32H7)
@ -732,12 +735,14 @@ mp_obj_t pyb_rtc_wakeup(size_t n_args, const mp_obj_t *args) {
#endif
// clear interrupt flags
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
#if defined(STM32G4)
RTC->ICSR &= ~RTC_ICSR_WUTWF;
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
RTC->SR &= ~RTC_SR_WUTF;
#else
RTC->ISR &= ~RTC_ISR_WUTF;
#endif
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
EXTI->PR1 = 1 << EXTI_RTC_WAKEUP;
#elif defined(STM32H7)
EXTI_D1->PR1 = 1 << EXTI_RTC_WAKEUP;
@ -757,7 +762,7 @@ mp_obj_t pyb_rtc_wakeup(size_t n_args, const mp_obj_t *args) {
RTC->WPR = 0xff;
// disable external interrupts on line EXTI_RTC_WAKEUP
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
EXTI->IMR1 &= ~(1 << EXTI_RTC_WAKEUP);
#elif defined(STM32H7)
EXTI_D1->IMR1 |= 1 << EXTI_RTC_WAKEUP;

View File

@ -529,7 +529,9 @@ void TAMP_STAMP_IRQHandler(void) {
void RTC_WKUP_IRQHandler(void) {
IRQ_ENTER(RTC_WKUP_IRQn);
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
#if defined(STM32G4)
RTC->MISR &= ~RTC_MISR_WUTMF; // clear wakeup interrupt flag
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xx) || defined(STM32H7B3xxQ)
RTC->SR &= ~RTC_SR_WUTF; // clear wakeup interrupt flag
#else
RTC->ISR &= ~RTC_ISR_WUTF; // clear wakeup interrupt flag
@ -593,7 +595,7 @@ void TIM1_BRK_TIM9_IRQHandler(void) {
IRQ_EXIT(TIM1_BRK_TIM9_IRQn);
}
#if defined(STM32L4)
#if defined(STM32G4) || defined(STM32L4)
void TIM1_BRK_TIM15_IRQHandler(void) {
IRQ_ENTER(TIM1_BRK_TIM15_IRQn);
timer_irq_handler(15);
@ -608,7 +610,7 @@ void TIM1_UP_TIM10_IRQHandler(void) {
IRQ_EXIT(TIM1_UP_TIM10_IRQn);
}
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
void TIM1_UP_TIM16_IRQHandler(void) {
IRQ_ENTER(TIM1_UP_TIM16_IRQn);
timer_irq_handler(1);
@ -631,7 +633,7 @@ void TIM1_TRG_COM_TIM11_IRQHandler(void) {
IRQ_EXIT(TIM1_TRG_COM_TIM11_IRQn);
}
#if defined(STM32L4) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
void TIM1_TRG_COM_TIM17_IRQHandler(void) {
IRQ_ENTER(TIM1_TRG_COM_TIM17_IRQn);
timer_irq_handler(17);
@ -679,12 +681,20 @@ void TIM6_DAC_IRQHandler(void) {
#endif
#if defined(TIM7) // STM32F401 doesn't have TIM7
#if defined(STM32G4)
void TIM7_DAC_IRQHandler(void) {
IRQ_ENTER(TIM7_DAC_IRQn);
timer_irq_handler(7);
IRQ_EXIT(TIM7_DAC_IRQn);
}
#else
void TIM7_IRQHandler(void) {
IRQ_ENTER(TIM7_IRQn);
timer_irq_handler(7);
IRQ_EXIT(TIM7_IRQn);
}
#endif
#endif
#if defined(TIM8) // STM32F401 doesn't have TIM8
void TIM8_BRK_TIM12_IRQHandler(void) {
@ -700,7 +710,7 @@ void TIM8_UP_TIM13_IRQHandler(void) {
IRQ_EXIT(TIM8_UP_TIM13_IRQn);
}
#if defined(STM32L4)
#if defined(STM32G4) || defined(STM32L4)
void TIM8_UP_IRQHandler(void) {
IRQ_ENTER(TIM8_UP_IRQn);
timer_irq_handler(8);

View File

@ -78,7 +78,7 @@
#include "py/mphal.h"
#include "powerctrl.h"
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32L4)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32L4)
void __fatal_error(const char *msg);
@ -171,10 +171,10 @@ void SystemClock_Config(void) {
RCC->DCKCFGR2 = 0;
#endif
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
#if defined(STM32H7)
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
#if defined(STM32G4) || defined(STM32H7)
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
#endif
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
@ -192,6 +192,10 @@ void SystemClock_Config(void) {
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
#elif defined(STM32G4)
// Configure the main internal regulator output voltage
HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST);
#elif defined(STM32L4)
// Configure LSE Drive Capability
__HAL_RCC_LSEDRIVE_CONFIG(RCC_LSEDRIVE_LOW);
@ -204,7 +208,7 @@ void SystemClock_Config(void) {
#endif
/* Enable HSE Oscillator and activate PLL with HSE as source */
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7)
RCC_OscInitStruct.OscillatorType = MICROPY_HW_RCC_OSCILLATOR_TYPE;
RCC_OscInitStruct.HSEState = MICROPY_HW_RCC_HSE_STATE;
RCC_OscInitStruct.HSIState = MICROPY_HW_RCC_HSI_STATE;
@ -240,6 +244,27 @@ void SystemClock_Config(void) {
#endif
#endif
#if defined(STM32G4)
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
#if MICROPY_HW_CLK_USE_HSI && MICROPY_HW_CLK_USE_HSI48
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSI48;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
#else
RCC_OscInitStruct.OscillatorType = MICROPY_HW_RCC_OSCILLATOR_TYPE;
RCC_OscInitStruct.HSEState = MICROPY_HW_RCC_HSE_STATE;
RCC_OscInitStruct.HSIState = MICROPY_HW_RCC_HSI_STATE;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
#endif
RCC_OscInitStruct.PLL.PLLM = MICROPY_HW_CLK_PLLM;
RCC_OscInitStruct.PLL.PLLN = MICROPY_HW_CLK_PLLN;
RCC_OscInitStruct.PLL.PLLP = MICROPY_HW_CLK_PLLP;
RCC_OscInitStruct.PLL.PLLQ = MICROPY_HW_CLK_PLLQ;
RCC_OscInitStruct.PLL.PLLR = MICROPY_HW_CLK_PLLR;
#endif
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
@ -295,7 +320,7 @@ void SystemClock_Config(void) {
RCC_OscInitStruct.PLL.PLLN = MICROPY_HW_CLK_PLLN;
RCC_OscInitStruct.PLL.PLLP = MICROPY_HW_CLK_PLLP;
RCC_OscInitStruct.PLL.PLLQ = MICROPY_HW_CLK_PLLQ;
#if defined(STM32L4) || defined(STM32H7)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32L4)
RCC_OscInitStruct.PLL.PLLR = MICROPY_HW_CLK_PLLR;
#endif
@ -309,6 +334,11 @@ void SystemClock_Config(void) {
RCC_ClkInitStruct.AHBCLKDivider = MICROPY_HW_CLK_AHB_DIV;
RCC_ClkInitStruct.APB1CLKDivider = MICROPY_HW_CLK_APB1_DIV;
RCC_ClkInitStruct.APB2CLKDivider = MICROPY_HW_CLK_APB2_DIV;
#elif defined(STM32G4)
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = MICROPY_HW_CLK_AHB_DIV;
RCC_ClkInitStruct.APB1CLKDivider = MICROPY_HW_CLK_APB1_DIV;
RCC_ClkInitStruct.APB2CLKDivider = MICROPY_HW_CLK_APB2_DIV;
#elif defined(STM32L4)
RCC_ClkInitStruct.AHBCLKDivider = MICROPY_HW_CLK_AHB_DIV;
RCC_ClkInitStruct.APB1CLKDivider = MICROPY_HW_CLK_APB1_DIV;
@ -351,12 +381,30 @@ void SystemClock_Config(void) {
}
#endif
#if defined(STM32G4)
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_8) != HAL_OK) {
__fatal_error("HAL_RCC_ClockConfig");
}
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC | RCC_PERIPHCLK_LPUART1
| RCC_PERIPHCLK_RNG | RCC_PERIPHCLK_ADC12
| RCC_PERIPHCLK_FDCAN | RCC_PERIPHCLK_USB;
PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1;
PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_HSE;
PeriphClkInitStruct.RngClockSelection = RCC_RNGCLKSOURCE_HSI48;
PeriphClkInitStruct.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) {
__fatal_error("HAL_RCCEx_PeriphCLKConfig");
}
#else
uint32_t vco_out = RCC_OscInitStruct.PLL.PLLN * (MICROPY_HW_CLK_VALUE / 1000000) / RCC_OscInitStruct.PLL.PLLM;
uint32_t sysclk_mhz = vco_out / RCC_OscInitStruct.PLL.PLLP;
bool need_pll48 = vco_out % 48 != 0;
if (powerctrl_rcc_clock_config_pll(&RCC_ClkInitStruct, sysclk_mhz, need_pll48) != 0) {
__fatal_error("HAL_RCC_ClockConfig");
}
#endif
#if defined(STM32H7)
/* Activate CSI clock mandatory for I/O Compensation Cell*/

View File

@ -482,7 +482,7 @@ STATIC void config_deadtime(pyb_timer_obj_t *self, mp_int_t ticks, mp_int_t brk)
deadTimeConfig.DeadTime = compute_dtg_from_ticks(ticks);
deadTimeConfig.BreakState = brk == BRK_OFF ? TIM_BREAK_DISABLE : TIM_BREAK_ENABLE;
deadTimeConfig.BreakPolarity = brk == BRK_LOW ? TIM_BREAKPOLARITY_LOW : TIM_BREAKPOLARITY_HIGH;
#if defined(STM32F7) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
#if defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32L4) || defined(STM32WB)
deadTimeConfig.BreakFilter = 0;
deadTimeConfig.Break2State = TIM_BREAK_DISABLE;
deadTimeConfig.Break2Polarity = TIM_BREAKPOLARITY_LOW;
@ -810,7 +810,7 @@ STATIC const uint32_t tim_instance_table[MICROPY_HW_MAX_TIMER] = {
TIM_ENTRY(1, TIM1_UP_TIM10_IRQn),
#elif defined(STM32H7)
TIM_ENTRY(1, TIM1_UP_IRQn),
#elif defined(STM32L4) || defined(STM32WB)
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32WB)
TIM_ENTRY(1, TIM1_UP_TIM16_IRQn),
#endif
#endif
@ -832,12 +832,16 @@ STATIC const uint32_t tim_instance_table[MICROPY_HW_MAX_TIMER] = {
#endif
#endif
#if defined(TIM7)
#if defined(STM32G4)
TIM_ENTRY(7, TIM7_DAC_IRQn),
#else
TIM_ENTRY(7, TIM7_IRQn),
#endif
#endif
#if defined(TIM8)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
TIM_ENTRY(8, TIM8_UP_TIM13_IRQn),
#elif defined(STM32L4)
#elif defined(STM32G4) || defined(STM32L4)
TIM_ENTRY(8, TIM8_UP_IRQn),
#endif
#endif
@ -882,6 +886,9 @@ STATIC const uint32_t tim_instance_table[MICROPY_HW_MAX_TIMER] = {
TIM_ENTRY(17, TIM1_TRG_COM_TIM17_IRQn),
#endif
#endif
#if defined(TIM20)
TIM_ENTRY(20, TIM20_UP_IRQn),
#endif
};
#undef TIM_ENTRY
@ -1401,6 +1408,7 @@ STATIC mp_obj_t pyb_timer_callback(mp_obj_t self_in, mp_obj_t callback) {
// start timer, so that it interrupts on overflow, but clear any
// pending interrupts which may have been set by initializing it.
__HAL_TIM_CLEAR_FLAG(&self->tim, TIM_IT_UPDATE);
HAL_TIM_Base_Stop(&self->tim); // internal timer state must be released before starting again
HAL_TIM_Base_Start_IT(&self->tim); // This will re-enable the IRQ
HAL_NVIC_EnableIRQ(self->irqn);
} else {

View File

@ -73,6 +73,15 @@
#define USART_CR3_IE_ALL (USART_CR3_IE_BASE)
#endif
#elif defined(STM32G4)
#define USART_CR1_IE_ALL (USART_CR1_IE_BASE | USART_CR1_EOBIE | USART_CR1_RTOIE | USART_CR1_CMIE)
#define USART_CR2_IE_ALL (USART_CR2_IE_BASE)
#if defined(USART_CR3_TCBGTIE)
#define USART_CR3_IE_ALL (USART_CR3_IE_BASE | USART_CR3_TCBGTIE | USART_CR3_WUFIE)
#else
#define USART_CR3_IE_ALL (USART_CR3_IE_BASE | USART_CR3_WUFIE)
#endif
#elif defined(STM32H7)
#define USART_CR1_IE_ALL (USART_CR1_IE_BASE | USART_CR1_RXFFIE | USART_CR1_TXFEIE | USART_CR1_EOBIE | USART_CR1_RTOIE | USART_CR1_CMIE)
#define USART_CR2_IE_ALL (USART_CR2_IE_BASE)
@ -91,6 +100,7 @@
#else
#define USART_CR3_IE_ALL (USART_CR3_IE_BASE | USART_CR3_WUFIE)
#endif
#endif
extern void NORETURN __fatal_error(const char *msg);
@ -501,6 +511,11 @@ bool uart_init(pyb_uart_obj_t *uart_obj,
huart.Init.Mode = UART_MODE_TX_RX;
huart.Init.HwFlowCtl = flow;
huart.Init.OverSampling = UART_OVERSAMPLING_16;
#if defined(STM32G4) // H7 and WB also have fifo..
huart.FifoMode = UART_FIFOMODE_ENABLE;
#endif
#if !defined(STM32F4)
huart.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
#endif
@ -798,14 +813,14 @@ uint32_t uart_get_baudrate(pyb_uart_obj_t *self) {
#if defined(LPUART1)
if (self->uart_id == PYB_LPUART_1) {
return LL_LPUART_GetBaudRate(self->uartx, uart_get_source_freq(self)
#if defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32WB)
, self->uartx->PRESC
#endif
);
}
#endif
return LL_USART_GetBaudRate(self->uartx, uart_get_source_freq(self),
#if defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32WB)
self->uartx->PRESC,
#endif
LL_USART_OVERSAMPLING_16);
@ -815,7 +830,7 @@ void uart_set_baudrate(pyb_uart_obj_t *self, uint32_t baudrate) {
#if defined(LPUART1)
if (self->uart_id == PYB_LPUART_1) {
LL_LPUART_SetBaudRate(self->uartx, uart_get_source_freq(self),
#if defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32WB)
LL_LPUART_PRESCALER_DIV1,
#endif
baudrate);
@ -823,7 +838,7 @@ void uart_set_baudrate(pyb_uart_obj_t *self, uint32_t baudrate) {
}
#endif
LL_USART_SetBaudRate(self->uartx, uart_get_source_freq(self),
#if defined(STM32H7) || defined(STM32WB)
#if defined(STM32G4) || defined(STM32H7) || defined(STM32WB)
LL_USART_PRESCALER_DIV1,
#endif
LL_USART_OVERSAMPLING_16, baudrate);
@ -874,7 +889,7 @@ int uart_rx_char(pyb_uart_obj_t *self) {
return data;
} else {
// no buffering
#if defined(STM32F0) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32F0) || defined(STM32F7) || defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
int data = self->uartx->RDR & self->char_mask;
self->uartx->ICR = USART_ICR_ORECF; // clear ORE if it was set
return data;
@ -1024,7 +1039,7 @@ void uart_irq_handler(mp_uint_t uart_id) {
uint16_t next_head = (self->read_buf_head + 1) % self->read_buf_len;
if (next_head != self->read_buf_tail) {
// only read data if room in buf
#if defined(STM32F0) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
#if defined(STM32F0) || defined(STM32F7) || defined(STM32G4) || defined(STM32L0) || defined(STM32L4) || defined(STM32H7) || defined(STM32WB)
int data = self->uartx->RDR; // clears UART_FLAG_RXNE
#else
self->mp_irq_flags = self->uartx->SR; // resample to get any new flags since next read of DR will clear SR

View File

@ -267,8 +267,12 @@ typedef struct _USBD_HandleTypeDef
with the DMA during the transaction process should be 4-bytes aligned */
#if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */