Merge pull request #5403 from blues/add-strm32l4t5-swan-support

stm32l4r5 Swan support
This commit is contained in:
Jeff Epler 2021-10-07 11:00:59 -05:00 committed by GitHub
commit 14ec6b70cf
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
59 changed files with 3503 additions and 180 deletions

View File

@ -111,6 +111,7 @@ CFLAGS += -Wno-undef -Wno-shadow -Wno-cast-align $(ADD_CFLAGS)
CFLAGS += -mthumb -mabi=aapcs-linux
# Arm core selection
MCU_FLAGS_L4 = -mcpu=cortex-m4
MCU_FLAGS_F4 = -mcpu=cortex-m4
MCU_FLAGS_F7 = -mcpu=cortex-m7
MCU_FLAGS_H7 = -mcpu=cortex-m7
@ -161,6 +162,13 @@ CFLAGS += \
-DCFG_TUD_MIDI_RX_BUFSIZE=128 \
-DCFG_TUD_MIDI_TX_BUFSIZE=128
ifdef CIRCUITPY_USB_VENDOR
CFLAGS += \
-DCFG_TUD_VENDOR_RX_BUFSIZE=1024 \
-DCFG_TUD_VENDOR_TX_BUFSIZE=1024
endif
SRC_STM32 = $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_,\
hal.c \
hal_adc.c \
@ -207,7 +215,7 @@ endif
# Need this to avoid UART linker problems. TODO: rewrite to use registered callbacks.
# Does not exist for F4 and lower
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx))
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx STM32L4R5xx))
SRC_STM32 += $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_hal_uart_ex.c
endif

View File

@ -0,0 +1,26 @@
/*
GNU linker script for STM32L4R5 with bootloader
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K /* entire flash */
FLASH_ISR (rx) : ORIGIN = 0x08010000, LENGTH = 4K /* ISR vector. Kind of wasteful. */
FLASH_FIRMWARE (rx) : ORIGIN = 0x08011000, LENGTH = 1024K-128K-64K-4K /* For now, limit to 1MB so that bank switching is still possible. */
FLASH_FS (rw) : ORIGIN = 0x080e0000, LENGTH = 128K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 640K
}
/* produce a link error if there is not this amount of RAM for these sections */
_minimum_stack_size = 24K;
_minimum_heap_size = 16K;
/* Define the top end of 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 = ORIGIN(RAM) + LENGTH(RAM);
/* RAM extents for the garbage collector */
_ram_start = ORIGIN(RAM);
_ram_end = ORIGIN(RAM) + LENGTH(RAM);

View File

@ -0,0 +1,29 @@
/*
GNU linker script for STM32L4R5 with filesystem
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K /* entire flash */
FLASH_ISR (rx) : ORIGIN = 0x08000000, LENGTH = 4K /* ISR vector. Kind of wasteful. */
FLASH_FIRMWARE (rx) : ORIGIN = 0x08001000, LENGTH = 1024K-128K-4K /* For now, limit to 1MB so that bank switching is still possible. */
FLASH_FS (rw) : ORIGIN = 0x080e0000, LENGTH = 128K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 640K
}
/* produce a link error if there is not this amount of RAM for these sections */
_minimum_stack_size = 24K;
_minimum_heap_size = 16K;
/* Define tho top end of 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 = ORIGIN(RAM) + LENGTH(RAM);
/* RAM extents for the garbage collector */
_ram_start = ORIGIN(RAM);
_ram_end = ORIGIN(RAM) + LENGTH(RAM);
/* ensure the firmware is within bounds */
ASSERT ( (ORIGIN(FLASH_FIRMWARE) + LENGTH(FLASH_FIRMWARE)) <= (ORIGIN(FLASH)+LENGTH(FLASH)), "FLASH_FIRMWARE out of bounds" );

View File

@ -0,0 +1,64 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 Scott Shawcroft for Adafruit Industries
*
* 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.
*/
#include "supervisor/board.h"
#include "mpconfigboard.h"
#include "stm32l4xx.h"
#include "stm32l4r5xx.h"
void initialize_discharge_pin(void) {
/* Initialize the 3V3 discharge to be OFF and the output power to be ON */
__HAL_RCC_GPIOE_CLK_ENABLE();
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_6;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
HAL_GPIO_WritePin(GPIOE, GPIO_PIN_6, GPIO_PIN_SET);
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pin = GPIO_PIN_4;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
HAL_GPIO_WritePin(GPIOE, GPIO_PIN_4, GPIO_PIN_SET);
}
void board_init(void) {
// enable the debugger while sleeping. Todo move somewhere more central (kind of generally useful in a debug build)
SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP);
// Set tick interrupt priority, default HAL value is intentionally invalid
// Without this, USB does not function.
HAL_InitTick((1UL << __NVIC_PRIO_BITS) - 1UL);
}
bool board_requests_safe_mode(void) {
return false;
}
void reset_board(void) {
initialize_discharge_pin();
}

View File

@ -0,0 +1,66 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors.
*
* 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.
*/
// Micropython setup
#define MICROPY_HW_BOARD_NAME "Swan R5"
#define MICROPY_HW_MCU_NAME "STM32L4R5ZIY6"
// todo - not sure why this isn't the default for this port
#define MICROPY_PY_SYS_PLATFORM MICROPY_HW_BOARD_NAME
#define STM32L4R5XX
#define BOARD_SWAN_R5
// The flash size is defined in the STM32L4xx HAL (but not for the F4)
// #define FLASH_SIZE (0x200000)
// #define FLASH_PAGE_SIZE (0x1000)
#define LSE_VALUE ((uint32_t)32768)
#define BOARD_HAS_LOW_SPEED_CRYSTAL (1)
#define BOARD_HAS_HIGH_SPEED_CRYSTAL (0)
// Bootloader only
#ifdef UF2_BOOTLOADER_ENABLED
#define BOARD_VTOR_DEFER (1) // Leave VTOR relocation to bootloader
#endif
#define BOARD_NO_VBUS_SENSE (1)
#define BOARD_NO_USB_OTG_ID_SENSE (1)
#define DEFAULT_I2C_BUS_SCL (&pin_PB06)
#define DEFAULT_I2C_BUS_SDA (&pin_PB07)
#define DEFAULT_SPI_BUS_SS (&pin_PD00)
#define DEFAULT_SPI_BUS_SCK (&pin_PD01)
#define DEFAULT_SPI_BUS_MOSI (&pin_PB15)
#define DEFAULT_SPI_BUS_MISO (&pin_PB14)
#define DEFAULT_UART_BUS_RX (&pin_PA10)
#define DEFAULT_UART_BUS_TX (&pin_PA09)

View File

@ -0,0 +1,73 @@
USB_VID = 0x30A4
USB_PID = 0x02
USB_PRODUCT = "Swan R5"
USB_MANUFACTURER = "Blues Inc."
INTERNAL_FLASH_FILESYSTEM = 1
MCU_SERIES = L4
MCU_VARIANT = STM32L4R5xx
MCU_PACKAGE = WLCSP144
LD_COMMON = boards/common_default.ld
LD_DEFAULT = boards/STM32L4R5_default.ld
# UF2 boot option
LD_BOOT = boards/STM32L4R5_boot.ld
UF2_OFFSET = 0x8010000
# Turn all of the below off while trying to get the thing to run
# These modules are implemented in ports/<port>/common-hal:
# Typically the first module to create
CIRCUITPY_MICROCONTROLLER = 1
CIRCUITPY_ALARM = 1
# Typically the second module to create
CIRCUITPY_DIGITALIO = 1
# Other modules:
CIRCUITPY_OS = 1
CIRCUITPY_STORAGE = 1
CIRCUITPY_USB_MSC = 1
CIRCUITPY_UDB_CDC = 1
CIRCUITPY_USB_VENDOR = 1
CIRCUITPY_NVM = 0
CIRCUITPY_ANALOGIO = 1
CIRCUITPY_BUSIO = 1
CIRCUITPY_NEOPIXEL_WRITE = 0
CIRCUITPY_PULSEIO = 1
CIRCUITPY_PWMIO = 1
CIRCUITPY_AUDIOPWMIO = 1
CIRCUITPY_CANIO = 0
CIRCUITPY_AUDIOBUSIO = 0
CIRCUITPY_I2CPERIPHERAL = 0
# Requires SPI, PulseIO (stub ok):
CIRCUITPY_DISPLAYIO = 0
# These modules are implemented in shared-module/ - they can be included in
# any port once their prerequisites in common-hal are complete.
# Requires DigitalIO:
CIRCUITPY_BITBANGIO = 1
# Requires DigitalIO
CIRCUITPY_GAMEPADSHIFT = 1
# Requires neopixel_write or SPI (dotstar)
CIRCUITPY_PIXELBUF = 0
# Requires OS
CIRCUITPY_RANDOM = 1
# Requires Microcontroller
CIRCUITPY_TOUCHIO = 1
# Requires USB
CIRCUITPY_USB_HID = 0
CIRCUITPY_USB_MIDI = 0
# Does nothing without I2C
CIRCUITPY_REQUIRE_I2C_PULLUPS = 0
# No requirements, but takes extra flash
CIRCUITPY_ULAB = 1
# requires SPI
CIRCUITPY_SDCARDIO = 0
CIRCUITPY_BLEIO_HCI = 0
CIRCUITPY_BLEIO = 0
CIRCUITPY_BUSDEVICE = 0
CIRCUITPY_KEYPAD = 1
CIRCUITPY_RGBMATRIX = 0

View File

@ -0,0 +1,50 @@
#include "py/objtuple.h"
#include "shared-bindings/board/__init__.h"
// Core Feather Pins
STATIC const mp_rom_map_elem_t board_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR_ENABLE_3V3), MP_ROM_PTR(&pin_PE04) },
{ MP_ROM_QSTR(MP_QSTR_DISCHARGE_3V3), MP_ROM_PTR(&pin_PE06) },
{ MP_ROM_QSTR(MP_QSTR_DISABLE_DISCHARGING), MP_ROM_TRUE },
{ MP_ROM_QSTR(MP_QSTR_ENABLE_DISCHARGING), MP_ROM_FALSE },
{ MP_ROM_QSTR(MP_QSTR_A0), MP_ROM_PTR(&pin_PA03) },
{ MP_ROM_QSTR(MP_QSTR_A1), MP_ROM_PTR(&pin_PA01) },
{ MP_ROM_QSTR(MP_QSTR_A2), MP_ROM_PTR(&pin_PC03) },
{ MP_ROM_QSTR(MP_QSTR_A3), MP_ROM_PTR(&pin_PC01) },
{ MP_ROM_QSTR(MP_QSTR_A4), MP_ROM_PTR(&pin_PC04) },
{ MP_ROM_QSTR(MP_QSTR_A5), MP_ROM_PTR(&pin_PC05) },
{ MP_ROM_QSTR(MP_QSTR_VOLTAGE_MONITOR), MP_ROM_PTR(&pin_PA00) },
{ MP_ROM_QSTR(MP_QSTR_BUTTON_USR), MP_ROM_PTR(&pin_PC13) },
{ MP_ROM_QSTR(MP_QSTR_SWITCH), MP_ROM_PTR(&pin_PE04) },
{ MP_ROM_QSTR(MP_QSTR_BUTTON), MP_ROM_PTR(&pin_PB02) }, // boot button, but looks like it's wired to GND on the schematic
{ MP_ROM_QSTR(MP_QSTR_D5), MP_ROM_PTR(&pin_PE11) },
{ MP_ROM_QSTR(MP_QSTR_D6), MP_ROM_PTR(&pin_PE09) },
{ MP_ROM_QSTR(MP_QSTR_D9), MP_ROM_PTR(&pin_PD15) },
{ MP_ROM_QSTR(MP_QSTR_D10), MP_ROM_PTR(&pin_PA04) }, // DAC1 output also
{ MP_ROM_QSTR(MP_QSTR_D11), MP_ROM_PTR(&pin_PA07) },
{ MP_ROM_QSTR(MP_QSTR_D12), MP_ROM_PTR(&pin_PA06) },
{ MP_ROM_QSTR(MP_QSTR_LED), MP_ROM_PTR(&pin_PE02) },
{ MP_ROM_QSTR(MP_QSTR_D13), MP_ROM_PTR(&pin_PA05) }, // DAC1 output also
{ MP_ROM_QSTR(MP_QSTR_SDA), MP_ROM_PTR(&pin_PB07) },
{ MP_ROM_QSTR(MP_QSTR_SCL), MP_ROM_PTR(&pin_PB06) },
{ MP_ROM_QSTR(MP_QSTR_DAC1), MP_ROM_PTR(&pin_PA04) }, // D10
{ MP_ROM_QSTR(MP_QSTR_DAC2), MP_ROM_PTR(&pin_PA05) }, // D13
{ MP_ROM_QSTR(MP_QSTR_SS), MP_ROM_PTR(&pin_PD00) },
{ MP_ROM_QSTR(MP_QSTR_SCK), MP_ROM_PTR(&pin_PD01) },
{ MP_ROM_QSTR(MP_QSTR_MISO), MP_ROM_PTR(&pin_PB14) },
{ MP_ROM_QSTR(MP_QSTR_MOSI), MP_ROM_PTR(&pin_PB15) },
{ MP_ROM_QSTR(MP_QSTR_TX), MP_ROM_PTR(&pin_PA09) },
{ MP_ROM_QSTR(MP_QSTR_RX), MP_ROM_PTR(&pin_PA10) },
{ MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&board_i2c_obj) },
{ MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&board_spi_obj) },
{ MP_ROM_QSTR(MP_QSTR_UART), MP_ROM_PTR(&board_uart_obj) },
};
MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table);

View File

@ -0,0 +1,85 @@
import board
import analogio
import digitalio
def test_dac_analog(p_in, p_out):
print(f"Running dac analog test with pin {p_in} as input and {p_out} as output\n")
pin_in = analogio.AnalogIn(p_in)
pin_out = analogio.AnalogOut(p_out)
for v in range(0, 65536, 4096):
pin_out.value = v
print(f"Value {v} read as {pin_in.value}")
pin_in.deinit()
pin_out.deinit()
def test_dac_digital(p_in, p_out):
print(f"Running dac digital test with pin {p_in} as input and {p_out} as output")
pin_in = digitalio.DigitalInOut(p_in)
pin_out = analogio.AnalogOut(p_out)
for v in range(0, 65536, 4096):
pin_out.value = v
print(f"Value {v} read as {pin_in.value}")
pin_in.deinit()
pin_out.deinit()
def test_dual(pair1, pair2):
# verifies that the DACs can be set independently
print(f"Running pair test\n")
pin1_in = analogio.AnalogIn(pair1[0])
pin1_out = analogio.AnalogOut(pair1[1])
pin2_in = analogio.AnalogIn(pair2[0])
pin2_out = analogio.AnalogOut(pair2[1])
for v in range(0, 65536, 4096):
v2 = 65535 - v
pin1_out.value = v
pin2_out.value = v2
print(f"Pair1: Value {v} read as {pin1_in.value}")
print(f"Pair2: Value {v2} read as {pin2_in.value}")
pin1_in.deinit()
pin1_out.deinit()
pin2_in.deinit()
pin2_out.deinit()
def test_analog_hilo(p_in, p_out):
print(f"Running analog hilo test with pin {p_in} as input and {p_out} as output")
pin_in = analogio.AnalogIn(p_in)
pin_out = digitalio.DigitalInOut(p_out)
pin_out.switch_to_output()
for v in (False, True, False, True):
pin_out.value = v
print(f"Value {v} read as {pin_in.value}")
pin_in.deinit()
pin_out.deinit()
def test_pair(pair):
# FIXME: test_analog_hilo works fine alone, but fails when the other dac functions are executed
test_analog_hilo(*pair)
test_dac_analog(*pair)
test_dac_digital(*pair)
def main():
pair1 = (board.A3, board.DAC1)
pair2 = (board.A2, board.DAC2)
print("running DAC1 tests")
test_pair(pair1)
print("running DAC2 tests")
test_pair(pair2)
print("running dual DAC tests")
test_dual(pair1, pair2)
main()

View File

@ -0,0 +1,148 @@
# SPDX-FileCopyrightText: 2018 Shawn Hymel for Adafruit Industries
#
# SPDX-License-Identifier: MIT
print("pins test")
"""
`adafruit_boardtest.boardtest_gpio`
====================================================
Toggles all available GPIO on a board. Verify their operation with an LED,
multimeter, another microcontroller, etc.
Run this script as its own main.py to individually run the test, or compile
with mpy-cross and call from separate test script.
* Author(s): Shawn Hymel for Adafruit Industries
Implementation Notes
--------------------
**Software and Dependencies:**
* Adafruit CircuitPython firmware for the supported boards:
https://github.com/adafruit/circuitpython/releases
"""
import time
import board
import digitalio
import supervisor
__version__ = "0.0.0-auto.0"
__repo__ = "https://github.com/adafruit/Adafruit_CircuitPython_BoardTest.git"
# Constants
LED_ON_DELAY_TIME = 0.2 # Seconds
LED_OFF_DELAY_TIME = 0.2 # Seconds
LED_PIN_NAMES = ["L", "LED", "RED_LED", "GREEN_LED", "BLUE_LED"]
# Test result strings
PASS = "PASS"
FAIL = "FAIL"
NA = "N/A"
# Determine if given value is a number
def _is_number(val):
try:
float(val)
return True
except ValueError:
return False
# Release pins
def _deinit_pins(gpios):
for g in gpios:
g.deinit()
# Toggle IO pins while waiting for answer
def _toggle_wait(pin_gpios):
timestamp = time.monotonic()
led_state = False
failed = []
for pg in pin_gpios:
(pin, gpio) = pg
print("Is pin %s toggling? [y/n]" % pin)
done = False
while not done:
if led_state:
if time.monotonic() > timestamp + LED_ON_DELAY_TIME:
led_state = False
timestamp = time.monotonic()
else:
if time.monotonic() > timestamp + LED_OFF_DELAY_TIME:
led_state = True
timestamp = time.monotonic()
gpio.value = led_state
if supervisor.runtime.serial_bytes_available:
answer = input()
if bool(answer == "y"):
done = True
elif bool(answer == "n"):
failed += pin
done = True
return failed
def buildPin(pin):
gpio = digitalio.DigitalInOut(pin)
return gpio
def run_test(pins):
"""
Toggles all available GPIO on and off repeatedly.
:param list[str] pins: list of pins to run the test on
:return: tuple(str, list[str]): test result followed by list of pins tested
"""
# Create a list of analog GPIO pins
analog_pins = [p for p in pins if p[0] == "A" and _is_number(p[1])]
# Create a list of digital GPIO
digital_pins = [p for p in pins if p[0] == "D" and _is_number(p[1])]
# Toggle LEDs if we find any
gpio_pins = analog_pins + digital_pins
if gpio_pins:
# Print out the LEDs found
print("GPIO pins found:", end=" ")
for pin in gpio_pins:
print(pin, end=" ")
print("\n")
# Create a list of IO objects for us to toggle
gpios = [buildPin(getattr(board, p)) for p in gpio_pins]
print("built GPIOs")
# Set all IO to output
for gpio in gpios:
gpio.direction = digitalio.Direction.OUTPUT
# Toggle pins while waiting for user to verify LEDs blinking
result = _toggle_wait(zip(gpio_pins, gpios))
# Release pins
_deinit_pins(gpios)
if result:
return FAIL, gpio_pins
return PASS, gpio_pins
# Else (no pins found)
print("No GPIO pins found")
return NA, []
run_test([p for p in dir(board)])

View File

@ -0,0 +1,22 @@
import board
import digitalio
import time
def monitor_button(pin, callback):
with digitalio.DigitalInOut(pin) as button:
newstate = not button.value # state is inverted
state = not newstate # ensure change reported to start with
while callback(newstate, newstate != state):
state = newstate
newstate = button.value
time.sleep(0.01)
def print_changes(state, changed):
if changed:
print(f"button pressed {state}")
return True
monitor_button(board.BUTTON_USR, print_changes)

View File

@ -0,0 +1,35 @@
# Background: I have a Swan R5 board running circuit python
# And I import the "board" module
import board
import digitalio
import supervisor
import time
# Scenario: Enable 3V3 pin defintiion
# Then the symbol "board.ENABLE_3V3" is defined
assert board.ENABLE_3V3 is not None
# Scenario: Discharge 3V3 definition
# Then the symbol "board.DISCHARGE_3V3" is defined
assert board.DISCHARGE_3V3 is not None
# And the symbol "board.DISABLE_DISCHARGING" is defined to be "True"
assert board.DISABLE_DISCHARGING is not None and board.DISABLE_DISCHARGING == True
# And the symbol "board.ENABLE_DISCHARGING" is defined to be "False"
assert board.ENABLE_DISCHARGING is not None and board.ENABLE_DISCHARGING == False
# Scenario: Toggle ENBLE_3V3
# Given I have a LED connected between the 3V3 and GND pins
# And ENABLE_3V3 is configured for output
_3v3 = digitalio.DigitalInOut(board.ENABLE_3V3)
_3v3.direction = digitalio.Direction.OUTPUT
# When I run code to toggle the pin at 0.5Hz
# Then I see the LED switch on and off at 0.5Hz
print("Toggling 3V3. Press a key to stop.")
while not supervisor.runtime.serial_bytes_available:
_3v3.value = True
time.sleep(1.0)
_3v3.value = False
time.sleep(1.0)
print("Toggling stopped.")

View File

@ -0,0 +1,20 @@
import board
import busio
i2c = busio.I2C(board.SCL, board.SDA)
count = 0
# Wait for I2C lock
while not i2c.try_lock():
pass
# Scan for devices on the I2C bus
print("Scanning I2C bus")
for x in i2c.scan():
print(hex(x))
count += 1
print("%d device(s) found on I2C bus" % count)
# Release the I2C bus
i2c.unlock()

View File

@ -0,0 +1,17 @@
import time
import pwmio
def fade(pin):
led = pwmio.PWMOut(pin, frequency=5000, duty_cycle=0)
# LED setup for QT Py M0:
# led = pwmio.PWMOut(board.SCK, frequency=5000, duty_cycle=0)
while True:
for i in range(100):
# PWM LED up and down
if i < 50:
led.duty_cycle = int(i * 2 * 65535 / 100) # Up
else:
led.duty_cycle = 65535 - int((i - 50) * 2 * 65535 / 100) # Down
time.sleep(0.01)

View File

@ -0,0 +1,58 @@
import board
import busio
import digitalio
cs = digitalio.DigitalInOut(board.SS)
cs.direction = digitalio.Direction.OUTPUT
cs.value = True
BME680_SPI_REGISTER = 0x73
BME680_CHIPID_REGISTER = 0xD0
BME680_CHIPID = 0x61
SPI_HERZ = 0x500000
spi = busio.SPI(board.SCK, MISO=board.MISO, MOSI=board.MOSI)
def readByte(addr):
value = -1
while not spi.try_lock():
pass
try:
spi.configure(baudrate=500000, phase=0, polarity=0)
cs.value = False
result = bytearray(1)
result[0] = addr | 0x80
spi.write(result)
spi.readinto(result)
value = result[0]
return value
finally:
spi.unlock()
cs.value = True
def writeByte(addr, value):
while not spi.try_lock():
pass
try:
spi.configure(baudrate=500000, phase=0, polarity=0)
cs.value = False
result = bytearray(2)
result[0] = addr & ~0x80
result[1] = value
spi.write(result)
finally:
spi.unlock()
# put the device in the correct mode to read the ID
reg = readByte(BME680_SPI_REGISTER)
if (reg & 16) != 0:
writeByte(BME680_SPI_REGISTER, reg & ~16)
id = readByte(BME680_CHIPID_REGISTER)
print(f"id is {id}, expected {BME680_CHIPID}")

View File

@ -0,0 +1,37 @@
import board
import busio
import digitalio
import usb_cdc
import time
while not usb_cdc.console.in_waiting:
time.sleep(0.1)
print("USART test")
# For most CircuitPython boards:
led = digitalio.DigitalInOut(board.LED)
# For QT Py M0:
# led = digitalio.DigitalInOut(board.SCK)
led.direction = digitalio.Direction.OUTPUT
uart = busio.UART(board.TX, board.RX, baudrate=9600)
while True:
data = uart.read(32) # read up to 32 bytes
# print(data) # this is a bytearray type
if data is not None:
led.value = True
# convert bytearray to string
data_string = "*".join([chr(b) for b in data])
print(data_string, end="")
led.value = False
if usb_cdc.console.in_waiting:
data = usb_cdc.console.read()
data_string = "*".join([chr(b) for b in data])
print("writing " + data_string)
uart.write(data)

View File

@ -0,0 +1,10 @@
import os
def main():
print("Random number test")
r = os.urandom(32)
print(f"urandom TRNG string is {r}")
main()

View File

@ -0,0 +1,375 @@
/*
* Taken from ST Cube library and modified. See below for original header.
*
* Modifications copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
/**
******************************************************************************
* @file system_stm32l4xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File
*
* This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32l4xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* After each device reset the MSI (4 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32l4xx.s" file, to
* configure the system clock before to branch to main program.
*
* This file configures the system clock as follows:
*=============================================================================
*-----------------------------------------------------------------------------
* System Clock source | MSI
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 4000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 4000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 1
*-----------------------------------------------------------------------------
* PLL_M | 1
*-----------------------------------------------------------------------------
* PLL_N | 8
*-----------------------------------------------------------------------------
* PLL_P | 7
*-----------------------------------------------------------------------------
* PLL_Q | 2
*-----------------------------------------------------------------------------
* PLL_R | 2
*-----------------------------------------------------------------------------
* PLLSAI1_P | NA
*-----------------------------------------------------------------------------
* PLLSAI1_Q | NA
*-----------------------------------------------------------------------------
* PLLSAI1_R | NA
*-----------------------------------------------------------------------------
* PLLSAI2_P | NA
*-----------------------------------------------------------------------------
* PLLSAI2_Q | NA
*-----------------------------------------------------------------------------
* PLLSAI2_R | NA
*-----------------------------------------------------------------------------
* Require 48MHz for USB OTG FS, | Disabled
* SDIO and RNG clock |
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Apache License, Version 2.0,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/Apache-2.0
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32l4xx_system
* @{
*/
/** @addtogroup STM32L4xx_System_Private_Includes
* @{
*/
#include "stm32l4xx.h"
#include <math.h>
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Defines
* @{
*/
#if !defined(HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined(MSI_VALUE)
#define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
#if !defined(HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/* Note: Following vector table addresses must be defined in line with linker
configuration. */
/*!< Uncomment the following line if you need to relocate the vector table
anywhere in Flash or Sram, else the vector table is kept at the automatic
remap of boot address selected */
/* #define USER_VECT_TAB_ADDRESS */
#if defined(USER_VECT_TAB_ADDRESS)
/*!< Uncomment the following line if you need to relocate your vector Table
in Sram else user remap will be done in Flash. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS SRAM1_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#else
#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#endif /* VECT_TAB_SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Variables
* @{
*/
/* The SystemCoreClock variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 4000000U;
const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
const uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \
4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U};
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system.
* @retval None
*/
void SystemInit(void) {
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 20U) | (3UL << 22U)); /* set CP10 and CP11 Full Access */
#endif
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Set MSION bit */
RCC->CR |= RCC_CR_MSION;
/* Reset CFGR register */
RCC->CFGR = 0x00000000U;
/* Reset HSEON, CSSON , HSION, and PLLON bits */
RCC->CR &= 0xEAF6FFFFU;
/* Reset PLLCFGR register */
RCC->PLLCFGR = 0x00001000U;
/* Reset HSEBYP bit */
RCC->CR &= 0xFFFBFFFFU;
/* Disable all interrupts */
RCC->CIER = 0x00000000U;
#if !(BOARD_VTOR_DEFER) // only set VTOR if the bootloader hasn't already
#if defined(USER_VECT_TAB_ADDRESS)
/* Configure the Vector Table location -------------------------------------*/
SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET;
#endif
#endif
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is MSI, SystemCoreClock will contain the MSI_VALUE(*)
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
* or HSI_VALUE(*) or MSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) MSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value
* 4 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value
* 16 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (***) HSE_VALUE is a constant defined in stm32l4xx_hal.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @retval None
*/
void SystemCoreClockUpdate(void) {
uint32_t tmp, msirange, pllvco, pllsource, pllm, pllr;
/* Get MSI Range frequency--------------------------------------------------*/
if ((RCC->CR & RCC_CR_MSIRGSEL) == 0U) { /* MSISRANGE from RCC_CSR applies */
msirange = (RCC->CSR & RCC_CSR_MSISRANGE) >> 8U;
} else { /* MSIRANGE from RCC_CR applies */
msirange = (RCC->CR & RCC_CR_MSIRANGE) >> 4U;
}
/*MSI frequency range in HZ*/
msirange = MSIRangeTable[msirange];
/* Get SYSCLK source -------------------------------------------------------*/
switch (RCC->CFGR & RCC_CFGR_SWS)
{
case 0x00: /* MSI used as system clock source */
SystemCoreClock = msirange;
break;
case 0x04: /* HSI used as system clock source */
SystemCoreClock = HSI_VALUE;
break;
case 0x08: /* HSE used as system clock source */
SystemCoreClock = HSE_VALUE;
break;
case 0x0C: /* PLL used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
SYSCLK = PLL_VCO / PLLR
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4U) + 1U;
switch (pllsource)
{
case 0x02: /* HSI used as PLL clock source */
pllvco = (HSI_VALUE / pllm);
break;
case 0x03: /* HSE used as PLL clock source */
pllvco = (HSE_VALUE / pllm);
break;
default: /* MSI used as PLL clock source */
pllvco = (msirange / pllm);
break;
}
pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8U);
pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25U) + 1U) * 2U;
SystemCoreClock = pllvco / pllr;
break;
default:
SystemCoreClock = msirange;
break;
}
/* Compute HCLK clock frequency --------------------------------------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4U)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -31,8 +31,17 @@
#include STM32_HAL_H
#define STM_BKPSRAM_SIZE 0x1000
#define STM_BKPSRAM_START BKPSRAM_BASE
#if CPY_STM32L4
#define __HAL_RCC_BKPSRAM_CLK_ENABLE()
#define STM_BKPSRAM_SIZE 0
#define STM_BKPSRAM_START 0
#define HAL_PWREx_EnableBkUpReg()
// backup RAM disabled for now. Will have the backup region at the top of SRAM3 which is retained.
#else
#define STM_BKPSRAM_SIZE 0x1000
#define STM_BKPSRAM_START BKPSRAM_BASE
#endif
STATIC bool initialized = false;

View File

@ -31,10 +31,20 @@
#include "shared-bindings/microcontroller/Pin.h"
#if CPY_STM32L4
#include "stm32l4xx_hal.h"
#include "stm32l4xx_ll_gpio.h"
#include "stm32l4xx_ll_adc.h"
#include "stm32l4xx_ll_bus.h"
#define ADC_SAMPLETIME ADC_SAMPLETIME_24CYCLES_5
#define LL_APB2_GRP1_PERIPH_ADC1 LL_AHB2_GRP1_PERIPH_ADC
#else
#include "stm32f4xx_hal.h"
#include "stm32f4xx_ll_gpio.h"
#include "stm32f4xx_ll_adc.h"
#include "stm32f4xx_ll_bus.h"
#define ADC_SAMPLETIME ADC_SAMPLETIME_15CYCLES
#endif
void common_hal_analogio_analogin_construct(analogio_analogin_obj_t *self,
const mcu_pin_obj_t *pin) {
@ -73,6 +83,55 @@ void common_hal_analogio_analogin_deinit(analogio_analogin_obj_t *self) {
self->pin = NULL;
}
uint32_t adc_channel(uint32_t channel) {
#if CPY_STM32L4
switch (channel) {
case 0:
return ADC_CHANNEL_0;
case 1:
return ADC_CHANNEL_1;
case 2:
return ADC_CHANNEL_2;
case 3:
return ADC_CHANNEL_3;
case 4:
return ADC_CHANNEL_4;
case 5:
return ADC_CHANNEL_5;
case 6:
return ADC_CHANNEL_6;
case 7:
return ADC_CHANNEL_7;
case 8:
return ADC_CHANNEL_8;
case 9:
return ADC_CHANNEL_9;
case 10:
return ADC_CHANNEL_10;
case 11:
return ADC_CHANNEL_11;
case 12:
return ADC_CHANNEL_12;
case 13:
return ADC_CHANNEL_13;
case 14:
return ADC_CHANNEL_14;
case 15:
return ADC_CHANNEL_15;
case 16:
return ADC_CHANNEL_16;
case 17:
return ADC_CHANNEL_17;
case 18:
return ADC_CHANNEL_18;
default:
return 0;
}
#else
return channel;
#endif
}
uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
// Something else might have used the ADC in a different way,
// so we completely re-initialize it.
@ -80,6 +139,9 @@ uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
if (self->pin->adc_unit & 0x01) {
ADCx = ADC1;
#if CPY_STM32L4
__HAL_RCC_ADC_CLK_ENABLE();
#endif
} else if (self->pin->adc_unit == 0x04) {
#ifdef ADC3
ADCx = ADC3;
@ -92,8 +154,8 @@ uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
// LL_GPIO_PIN_0
// HAL Implementation
ADC_HandleTypeDef AdcHandle;
ADC_ChannelConfTypeDef sConfig;
ADC_HandleTypeDef AdcHandle = {};
ADC_ChannelConfTypeDef sConfig = {};
AdcHandle.Instance = ADCx;
AdcHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2;
@ -102,20 +164,42 @@ uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
AdcHandle.Init.ContinuousConvMode = DISABLE;
AdcHandle.Init.DiscontinuousConvMode = DISABLE;
AdcHandle.Init.NbrOfDiscConversion = 0;
AdcHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
AdcHandle.Init.ExternalTrigConv = ADC_SOFTWARE_START;
AdcHandle.Init.DataAlign = ADC_DATAALIGN_RIGHT;
AdcHandle.Init.NbrOfConversion = 1;
AdcHandle.Init.DMAContinuousRequests = DISABLE;
AdcHandle.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
HAL_ADC_Init(&AdcHandle);
#ifdef ADC_OVR_DATA_OVERWRITTEN
AdcHandle.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN; /* DR register is overwritten with the last conversion result in case of overrun */
#endif
sConfig.Channel = (uint32_t)self->pin->adc_channel; // ADC_CHANNEL_0 <-normal iteration, not mask
if (HAL_ADC_Init(&AdcHandle) != HAL_OK) {
return 0;
}
sConfig.Channel = adc_channel(self->pin->adc_channel); // ADC_CHANNEL_0 <-normal iteration, not mask
sConfig.Rank = 1;
sConfig.SamplingTime = ADC_SAMPLETIME_15CYCLES; // Taken from micropython
HAL_ADC_ConfigChannel(&AdcHandle, &sConfig);
HAL_ADC_Start(&AdcHandle);
sConfig.SamplingTime = ADC_SAMPLETIME;
#if CPY_STM32L4
sConfig.SingleDiff = ADC_SINGLE_ENDED; /* Single-ended input channel */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
if (!IS_ADC_CHANNEL(&AdcHandle, sConfig.Channel)) {
return 0;
}
#endif
if (HAL_ADC_ConfigChannel(&AdcHandle, &sConfig) != HAL_OK) {
return 0;
}
#if CPY_STM32L4
if (HAL_ADCEx_Calibration_Start(&AdcHandle, ADC_SINGLE_ENDED) != HAL_OK) {
return 0;
}
#endif
if (HAL_ADC_Start(&AdcHandle) != HAL_OK) {
return 0;
}
HAL_ADC_PollForConversion(&AdcHandle,1);
uint16_t value = (uint16_t)HAL_ADC_GetValue(&AdcHandle);
HAL_ADC_Stop(&AdcHandle);

View File

@ -37,7 +37,14 @@
#include "common-hal/microcontroller/Pin.h"
#include "stm32f4xx_hal.h"
#include STM32_HAL_H
#ifndef __HAL_RCC_DAC_CLK_ENABLE
#define __HAL_RCC_DAC_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE
#endif
#ifndef __HAL_RCC_DAC_CLK_DISABLE
#define __HAL_RCC_DAC_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE
#endif
// DAC is shared between both channels.
#if HAS_DAC

View File

@ -31,7 +31,11 @@
#include "common-hal/microcontroller/Pin.h"
#include "py/obj.h"
#if CPY_STM32L4
#include "stm32l4xx_hal.h"
#else
#include "stm32f4xx_hal.h"
#endif
#include "peripherals/periph.h"
typedef struct {

View File

@ -50,6 +50,13 @@
#ifndef CPY_I2CSTANDARD_TIMINGR
#define CPY_I2CSTANDARD_TIMINGR 0x307075B1
#endif
#elif (CPY_STM32L4)
#ifndef CPY_I2CFAST_TIMINGR
#define CPY_I2CFAST_TIMINGR 0x00B03FDB
#endif
#ifndef CPY_I2CSTANDARD_TIMINGR
#define CPY_I2CSTANDARD_TIMINGR 0x307075B1
#endif
#endif
// Arrays use 0 based numbering: I2C1 is stored at index 0
@ -142,7 +149,7 @@ void common_hal_busio_i2c_construct(busio_i2c_obj_t *self,
i2c_assign_irq(self, I2Cx);
// Handle the HAL handle differences
#if (CPY_STM32H7 || CPY_STM32F7)
#if (CPY_STM32H7 || CPY_STM32F7 || CPY_STM32L4)
if (frequency == 400000) {
self->handle.Init.Timing = CPY_I2CFAST_TIMINGR;
} else if (frequency == 100000) {

View File

@ -58,7 +58,7 @@ STATIC uint32_t get_busclock(SPI_TypeDef *instance) {
} else {
return HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SPI6);
}
#elif (CPY_STM32F4 || CPY_STM32F7)
#elif (CPY_STM32F4 || CPY_STM32F7 || CPY_STM32L4)
// SPI2 and 3 are on PCLK1, if they exist.
#ifdef SPI2
if (instance == SPI2) {

View File

@ -33,8 +33,7 @@
#include "common-hal/canio/__init__.h"
#include "shared-module/canio/Message.h"
#include "stm32f4xx_hal.h"
#include "stm32f4xx_hal_can.h"
#include STM32_HAL_H
#define FILTER_BANK_COUNT (28)

View File

@ -37,6 +37,10 @@
#include "stm32f7xx_ll_gpio.h"
#elif (CPY_STM32F4)
#include "stm32f4xx_ll_gpio.h"
#elif (CPY_STM32L4)
#include "stm32l4xx_ll_gpio.h"
#else
#error unknown MCU for DigitalInOut
#endif
void common_hal_digitalio_digitalinout_never_reset(

View File

@ -33,7 +33,7 @@
#if defined(TFBGA216)
GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH, GPIOI, GPIOJ, GPIOK};
#elif defined(LQFP144)
#elif defined(LQFP144) || defined(WLCSP144)
GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG};
#elif defined(LQFP100_f4) || (LQFP100_x7)
GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC, GPIOD, GPIOE};
@ -41,6 +41,8 @@ GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC, GPIOD, GPIOE};
GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC, GPIOD};
#elif defined(UFQFPN48)
GPIO_TypeDef *ports[] = {GPIOA, GPIOB, GPIOC};
#else
#error Unknown package type
#endif

View File

@ -26,8 +26,7 @@
#include "common-hal/nvm/ByteArray.h"
#include "stm32f4xx_hal.h"
#include STM32_HAL_H
#include "supervisor/shared/stack.h"
#include <stdint.h>

View File

@ -62,7 +62,11 @@ STATIC void pulsein_exti_event_handler(uint8_t num) {
uint32_t current_count = tim_handle.Instance->CNT;
// Interrupt register must be cleared manually
#if CPY_STM32L4
EXTI->PR1 = 1 << num;
#else
EXTI->PR = 1 << num;
#endif
pulseio_pulsein_obj_t *self = callback_obj_ref[num];
if (!self) {

View File

@ -386,6 +386,7 @@ void assert_failed(uint8_t *file, uint32_t line);
#define CPY_STM32F4 1
#define CPY_STM32F7 0
#define CPY_STM32H7 0
#define CPY_STM32L4 0
#endif /* __STM32F4xx_HAL_CONF_H */

View File

@ -391,6 +391,8 @@ void assert_failed(uint8_t *file, uint32_t line);
#define CPY_STM32F4 0
#define CPY_STM32F7 1
#define CPY_STM32H7 0
#define CPY_STM32L4 0
#endif /* __STM32F7xx_HAL_CONF_H */

View File

@ -436,6 +436,8 @@ void assert_failed(uint8_t *file, uint32_t line);
#define CPY_STM32F4 0
#define CPY_STM32F7 0
#define CPY_STM32H7 1
#define CPY_STM32L4 0
#endif /* __STM32H7xx_HAL_CONF_H */

View File

@ -0,0 +1,480 @@
/**
******************************************************************************
* @file stm32l4xx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32l4xx_hal_conf.h.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
#include "stm32_hal_conf.h"
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32L4xx_HAL_CONF_H
#define STM32L4xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_CAN_MODULE_ENABLED
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
#define HAL_COMP_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_CRYP_MODULE_ENABLED
#define HAL_DAC_MODULE_ENABLED
#define HAL_DCMI_MODULE_ENABLED
#define HAL_DFSDM_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_DMA2D_MODULE_ENABLED
#define HAL_DSI_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_FIREWALL_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GFXMMU_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_HASH_MODULE_ENABLED
#define HAL_HCD_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_IRDA_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_LCD_MODULE_ENABLED
#define HAL_LPTIM_MODULE_ENABLED
#define HAL_LTDC_MODULE_ENABLED
#define HAL_MMC_MODULE_ENABLED
#define HAL_NAND_MODULE_ENABLED
#define HAL_NOR_MODULE_ENABLED
#define HAL_OPAMP_MODULE_ENABLED
#define HAL_OSPI_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_SD_MODULE_ENABLED
#define HAL_SMARTCARD_MODULE_ENABLED
#define HAL_SMBUS_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_SRAM_MODULE_ENABLED
#define HAL_SWPMI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_TSC_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_WWDG_MODULE_ENABLED
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined(HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined(HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal Multiple Speed oscillator (MSI) default value.
* This value is the default MSI range value after Reset.
*/
#if !defined(MSI_VALUE)
#define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined(HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG.
* This internal oscillator is mainly dedicated to provide a high precision clock to
* the USB peripheral by means of a special Clock Recovery System (CRS) circuitry.
* When the CRS is not used, the HSI48 RC oscillator runs on it default frequency
* which is subject to manufacturing process variations.
*/
#if !defined(HSI48_VALUE)
#define HSI48_VALUE 48000000U /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz.
The real value my vary depending on manufacturing process variations.*/
#endif /* HSI48_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined(LSI_VALUE)
#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature.*/
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined(LSE_VALUE)
#define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined(LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for SAI1 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined(EXTERNAL_SAI1_CLOCK_VALUE)
#define EXTERNAL_SAI1_CLOCK_VALUE 48000U /*!< Value of the SAI1 External clock source in Hz*/
#endif /* EXTERNAL_SAI1_CLOCK_VALUE */
/**
* @brief External clock source for SAI2 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined(EXTERNAL_SAI2_CLOCK_VALUE)
#define EXTERNAL_SAI2_CLOCK_VALUE 48000U /*!< Value of the SAI2 External clock source in Hz*/
#endif /* EXTERNAL_SAI2_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 0U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Register callback feature configuration ############### */
/**
* @brief Set below the peripheral configuration to "1U" to add the support
* of HAL callback registration/deregistration feature for the HAL
* driver(s). This allows user application to provide specific callback
* functions thanks to HAL_PPP_RegisterCallback() rather than overwriting
* the default weak callback functions (see each stm32l4xx_hal_ppp.h file
* for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef
* for each PPP peripheral).
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U
#define USE_HAL_GFXMMU_REGISTER_CALLBACKS 0U
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U
#define USE_HAL_OSPI_REGISTER_CALLBACKS 0U
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U
#define USE_HAL_SD_REGISTER_CALLBACKS 0U
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U
#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U
#define USE_HAL_TSC_REGISTER_CALLBACKS 0U
#define USE_HAL_UART_REGISTER_CALLBACKS 0U
#define USE_HAL_USART_REGISTER_CALLBACKS 0U
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 1U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32l4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32l4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32l4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_DFSDM_MODULE_ENABLED
#include "stm32l4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32l4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32l4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32l4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "Legacy/stm32l4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32l4xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32l4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32l4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32l4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_DCMI_MODULE_ENABLED
#include "stm32l4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
#include "stm32l4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */
#ifdef HAL_DSI_MODULE_ENABLED
#include "stm32l4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32l4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_GFXMMU_MODULE_ENABLED
#include "stm32l4xx_hal_gfxmmu.h"
#endif /* HAL_GFXMMU_MODULE_ENABLED */
#ifdef HAL_FIREWALL_MODULE_ENABLED
#include "stm32l4xx_hal_firewall.h"
#endif /* HAL_FIREWALL_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32l4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32l4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32l4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32l4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32l4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32l4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32l4xx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32l4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_LTDC_MODULE_ENABLED
#include "stm32l4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32l4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32l4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32l4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32l4xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_OSPI_MODULE_ENABLED
#include "stm32l4xx_hal_ospi.h"
#endif /* HAL_OSPI_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32l4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32l4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32l4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32l4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32l4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32l4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32l4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32l4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32l4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32l4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32l4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_SWPMI_MODULE_ENABLED
#include "stm32l4xx_hal_swpmi.h"
#endif /* HAL_SWPMI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32l4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32l4xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32l4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32l4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32l4xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
// CircuitPython specific conditionals. Using a value is better than checking
// defined because undefined variable happen when a file isn't included when it
// should have been.
#define CPY_STM32F4 0
#define CPY_STM32F7 0
#define CPY_STM32H7 0
#define CPY_STM32L4 1
#endif /* STM32L4xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -51,6 +51,9 @@ extern uint8_t _ld_default_stack_size;
#ifndef BOARD_NO_VBUS_SENSE
#define BOARD_NO_VBUS_SENSE (0)
#endif
#ifndef BOARD_NO_USB_OTG_ID_SENSE
#define BOARD_NO_USB_OTG_ID_SENSE (0)
#endif
// Peripheral implementation counts
#define MAX_UART 10

View File

@ -62,4 +62,22 @@ ifeq ($(MCU_SERIES),F7)
USB_NUM_ENDPOINT_PAIRS = 6
endif
ifeq ($(MCU_SERIES),L4)
# Not yet implemented common-hal modules:
CIRCUITPY_ANALOGIO ?= 0
CIRCUITPY_AUDIOBUSIO ?= 0
CIRCUITPY_AUDIOIO ?= 0
CIRCUITPY_COUNTIO ?= 0
CIRCUITPY_FREQUENCYIO ?= 0
CIRCUITPY_I2CPERIPHERAL ?= 0
CIRCUITPY_NEOPIXEL_WRITE ?= 0
CIRCUITPY_NVM ?= 0
CIRCUITPY_ROTARYIO ?= 0
CIRCUITPY_RTC ?= 0
# todo - this varies between devices in the series
# This slide deck https://www.st.com/content/ccc/resource/training/technical/product_training/98/89/c8/6c/3e/e9/49/79/STM32L4_Peripheral_USB.pdf/files/STM32L4_Peripheral_USB.pdf/jcr:content/translations/en.STM32L4_Peripheral_USB.pdf
# cites 16 endpoints, 8 endpoint pairs, while section 3.39 of the L4R5 datasheet states 6 endpoint pairs.
USB_NUM_ENDPOINT_PAIRS = 6
endif
CIRCUITPY_PARALLELDISPLAY := 0

View File

@ -0,0 +1,159 @@
#include "shared-bindings/microcontroller/__init__.h"
#include "common-hal/microcontroller/Pin.h"
#include "py/obj.h"
STATIC const mp_rom_map_elem_t mcu_pin_globals_table[] = {
// Pins 1-36
{ MP_ROM_QSTR(MP_QSTR_PE02), MP_ROM_PTR(&pin_PE02) },
{ MP_ROM_QSTR(MP_QSTR_PE03), MP_ROM_PTR(&pin_PE03) },
{ MP_ROM_QSTR(MP_QSTR_PE04), MP_ROM_PTR(&pin_PE04) },
{ MP_ROM_QSTR(MP_QSTR_PE05), MP_ROM_PTR(&pin_PE05) },
{ MP_ROM_QSTR(MP_QSTR_PE06), MP_ROM_PTR(&pin_PE06) },
/* VBAT -------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PC13), MP_ROM_PTR(&pin_PC13) },
// PC14 OSC32_IN ----------------------------------*/
// PC15 OSC32_OUT ---------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PF00), MP_ROM_PTR(&pin_PF00) },
{ MP_ROM_QSTR(MP_QSTR_PF01), MP_ROM_PTR(&pin_PF01) },
{ MP_ROM_QSTR(MP_QSTR_PF02), MP_ROM_PTR(&pin_PF02) },
{ MP_ROM_QSTR(MP_QSTR_PF03), MP_ROM_PTR(&pin_PF03) },
{ MP_ROM_QSTR(MP_QSTR_PF04), MP_ROM_PTR(&pin_PF04) },
{ MP_ROM_QSTR(MP_QSTR_PF05), MP_ROM_PTR(&pin_PF05) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PF06), MP_ROM_PTR(&pin_PF06) },
{ MP_ROM_QSTR(MP_QSTR_PF07), MP_ROM_PTR(&pin_PF07) },
{ MP_ROM_QSTR(MP_QSTR_PF08), MP_ROM_PTR(&pin_PF08) },
{ MP_ROM_QSTR(MP_QSTR_PF09), MP_ROM_PTR(&pin_PF09) },
{ MP_ROM_QSTR(MP_QSTR_PF10), MP_ROM_PTR(&pin_PF10) },
// PH0 OSC_IN -------------------------------------*/
// PH1 OSC_OUT ------------------------------------*/
// NRST -------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PC00), MP_ROM_PTR(&pin_PC00) },
{ MP_ROM_QSTR(MP_QSTR_PC01), MP_ROM_PTR(&pin_PC01) },
{ MP_ROM_QSTR(MP_QSTR_PC02), MP_ROM_PTR(&pin_PC02) },
{ MP_ROM_QSTR(MP_QSTR_PC03), MP_ROM_PTR(&pin_PC03) },
// VDD --------------------------------------------*/
// VSSA -------------------------------------------*/
// VREF+ ------------------------------------------*/
// VDDA -------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PA00), MP_ROM_PTR(&pin_PA00) },
{ MP_ROM_QSTR(MP_QSTR_PA01), MP_ROM_PTR(&pin_PA01) },
{ MP_ROM_QSTR(MP_QSTR_PA02), MP_ROM_PTR(&pin_PA02) },
// Pins 37-72
{ MP_ROM_QSTR(MP_QSTR_PA03), MP_ROM_PTR(&pin_PA03) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PA04), MP_ROM_PTR(&pin_PA04) },
{ MP_ROM_QSTR(MP_QSTR_PA05), MP_ROM_PTR(&pin_PA05) },
{ MP_ROM_QSTR(MP_QSTR_PA06), MP_ROM_PTR(&pin_PA06) },
{ MP_ROM_QSTR(MP_QSTR_PA07), MP_ROM_PTR(&pin_PA07) },
{ MP_ROM_QSTR(MP_QSTR_PC04), MP_ROM_PTR(&pin_PC04) },
{ MP_ROM_QSTR(MP_QSTR_PC05), MP_ROM_PTR(&pin_PC05) },
{ MP_ROM_QSTR(MP_QSTR_PB00), MP_ROM_PTR(&pin_PB00) },
{ MP_ROM_QSTR(MP_QSTR_PB01), MP_ROM_PTR(&pin_PB01) },
{ MP_ROM_QSTR(MP_QSTR_PB02), MP_ROM_PTR(&pin_PB02) },
{ MP_ROM_QSTR(MP_QSTR_PF11), MP_ROM_PTR(&pin_PF11) },
{ MP_ROM_QSTR(MP_QSTR_PF12), MP_ROM_PTR(&pin_PF12) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PF13), MP_ROM_PTR(&pin_PF13) },
{ MP_ROM_QSTR(MP_QSTR_PF14), MP_ROM_PTR(&pin_PF14) },
{ MP_ROM_QSTR(MP_QSTR_PF15), MP_ROM_PTR(&pin_PF15) },
{ MP_ROM_QSTR(MP_QSTR_PG00), MP_ROM_PTR(&pin_PG00) },
{ MP_ROM_QSTR(MP_QSTR_PG01), MP_ROM_PTR(&pin_PG01) },
{ MP_ROM_QSTR(MP_QSTR_PE07), MP_ROM_PTR(&pin_PE07) },
{ MP_ROM_QSTR(MP_QSTR_PE08), MP_ROM_PTR(&pin_PE08) },
{ MP_ROM_QSTR(MP_QSTR_PE09), MP_ROM_PTR(&pin_PE09) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PE10), MP_ROM_PTR(&pin_PE10) },
{ MP_ROM_QSTR(MP_QSTR_PE11), MP_ROM_PTR(&pin_PE11) },
{ MP_ROM_QSTR(MP_QSTR_PE12), MP_ROM_PTR(&pin_PE12) },
{ MP_ROM_QSTR(MP_QSTR_PE13), MP_ROM_PTR(&pin_PE13) },
{ MP_ROM_QSTR(MP_QSTR_PE14), MP_ROM_PTR(&pin_PE14) },
{ MP_ROM_QSTR(MP_QSTR_PE15), MP_ROM_PTR(&pin_PE15) },
{ MP_ROM_QSTR(MP_QSTR_PB10), MP_ROM_PTR(&pin_PB10) },
{ MP_ROM_QSTR(MP_QSTR_PB11), MP_ROM_PTR(&pin_PB11) },
// VCAP1 ------------------------------------------*/
// VDD --------------------------------------------*/
// Pins 73-108
{ MP_ROM_QSTR(MP_QSTR_PB12), MP_ROM_PTR(&pin_PB12) },
{ MP_ROM_QSTR(MP_QSTR_PB13), MP_ROM_PTR(&pin_PB13) },
{ MP_ROM_QSTR(MP_QSTR_PB14), MP_ROM_PTR(&pin_PB14) },
{ MP_ROM_QSTR(MP_QSTR_PB15), MP_ROM_PTR(&pin_PB15) },
{ MP_ROM_QSTR(MP_QSTR_PD08), MP_ROM_PTR(&pin_PD08) },
{ MP_ROM_QSTR(MP_QSTR_PD09), MP_ROM_PTR(&pin_PD09) },
{ MP_ROM_QSTR(MP_QSTR_PD10), MP_ROM_PTR(&pin_PD10) },
{ MP_ROM_QSTR(MP_QSTR_PD11), MP_ROM_PTR(&pin_PD11) },
{ MP_ROM_QSTR(MP_QSTR_PD12), MP_ROM_PTR(&pin_PD12) },
{ MP_ROM_QSTR(MP_QSTR_PD13), MP_ROM_PTR(&pin_PD13) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PD14), MP_ROM_PTR(&pin_PD14) },
{ MP_ROM_QSTR(MP_QSTR_PD15), MP_ROM_PTR(&pin_PD15) },
{ MP_ROM_QSTR(MP_QSTR_PG02), MP_ROM_PTR(&pin_PG02) },
{ MP_ROM_QSTR(MP_QSTR_PG03), MP_ROM_PTR(&pin_PG03) },
{ MP_ROM_QSTR(MP_QSTR_PG04), MP_ROM_PTR(&pin_PG04) },
{ MP_ROM_QSTR(MP_QSTR_PG05), MP_ROM_PTR(&pin_PG05) },
{ MP_ROM_QSTR(MP_QSTR_PG06), MP_ROM_PTR(&pin_PG06) },
{ MP_ROM_QSTR(MP_QSTR_PG07), MP_ROM_PTR(&pin_PG07) },
{ MP_ROM_QSTR(MP_QSTR_PG08), MP_ROM_PTR(&pin_PG08) },
// VSS --------------------------------------------*/
// VDD or VDD_USB (F412, F446) --------------------*/
{ MP_ROM_QSTR(MP_QSTR_PC06), MP_ROM_PTR(&pin_PC06) },
{ MP_ROM_QSTR(MP_QSTR_PC07), MP_ROM_PTR(&pin_PC07) },
{ MP_ROM_QSTR(MP_QSTR_PC08), MP_ROM_PTR(&pin_PC08) },
{ MP_ROM_QSTR(MP_QSTR_PC09), MP_ROM_PTR(&pin_PC09) },
{ MP_ROM_QSTR(MP_QSTR_PA08), MP_ROM_PTR(&pin_PA08) },
{ MP_ROM_QSTR(MP_QSTR_PA09), MP_ROM_PTR(&pin_PA09) },
{ MP_ROM_QSTR(MP_QSTR_PA10), MP_ROM_PTR(&pin_PA10) },
{ MP_ROM_QSTR(MP_QSTR_PA11), MP_ROM_PTR(&pin_PA11) },
{ MP_ROM_QSTR(MP_QSTR_PA12), MP_ROM_PTR(&pin_PA12) },
{ MP_ROM_QSTR(MP_QSTR_PA13), MP_ROM_PTR(&pin_PA13) },
// VCAP2 ------------------------------------------*/
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
// Pins 109-144
{ MP_ROM_QSTR(MP_QSTR_PA14), MP_ROM_PTR(&pin_PA14) },
{ MP_ROM_QSTR(MP_QSTR_PA15), MP_ROM_PTR(&pin_PA15) },
{ MP_ROM_QSTR(MP_QSTR_PC10), MP_ROM_PTR(&pin_PC10) },
{ MP_ROM_QSTR(MP_QSTR_PC11), MP_ROM_PTR(&pin_PC11) },
{ MP_ROM_QSTR(MP_QSTR_PC12), MP_ROM_PTR(&pin_PC12) },
{ MP_ROM_QSTR(MP_QSTR_PD00), MP_ROM_PTR(&pin_PD00) },
{ MP_ROM_QSTR(MP_QSTR_PD01), MP_ROM_PTR(&pin_PD01) },
{ MP_ROM_QSTR(MP_QSTR_PD02), MP_ROM_PTR(&pin_PD02) },
{ MP_ROM_QSTR(MP_QSTR_PD03), MP_ROM_PTR(&pin_PD03) },
{ MP_ROM_QSTR(MP_QSTR_PD04), MP_ROM_PTR(&pin_PD04) },
{ MP_ROM_QSTR(MP_QSTR_PD05), MP_ROM_PTR(&pin_PD05) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PD06), MP_ROM_PTR(&pin_PD06) },
{ MP_ROM_QSTR(MP_QSTR_PD07), MP_ROM_PTR(&pin_PD07) },
{ MP_ROM_QSTR(MP_QSTR_PG09), MP_ROM_PTR(&pin_PG09) },
{ MP_ROM_QSTR(MP_QSTR_PG10), MP_ROM_PTR(&pin_PG10) },
{ MP_ROM_QSTR(MP_QSTR_PG11), MP_ROM_PTR(&pin_PG11) },
{ MP_ROM_QSTR(MP_QSTR_PG12), MP_ROM_PTR(&pin_PG12) },
{ MP_ROM_QSTR(MP_QSTR_PG13), MP_ROM_PTR(&pin_PG13) },
{ MP_ROM_QSTR(MP_QSTR_PG14), MP_ROM_PTR(&pin_PG14) },
// VSS --------------------------------------------*/
// VDD --------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PG15), MP_ROM_PTR(&pin_PG15) },
{ MP_ROM_QSTR(MP_QSTR_PB03), MP_ROM_PTR(&pin_PB03) },
{ MP_ROM_QSTR(MP_QSTR_PB04), MP_ROM_PTR(&pin_PB04) },
{ MP_ROM_QSTR(MP_QSTR_PB05), MP_ROM_PTR(&pin_PB05) },
{ MP_ROM_QSTR(MP_QSTR_PB06), MP_ROM_PTR(&pin_PB06) },
{ MP_ROM_QSTR(MP_QSTR_PB07), MP_ROM_PTR(&pin_PB07) },
// BOOT0 ------------------------------------------*/
{ MP_ROM_QSTR(MP_QSTR_PB08), MP_ROM_PTR(&pin_PB08) },
{ MP_ROM_QSTR(MP_QSTR_PB09), MP_ROM_PTR(&pin_PB09) },
{ MP_ROM_QSTR(MP_QSTR_PE00), MP_ROM_PTR(&pin_PE00) },
{ MP_ROM_QSTR(MP_QSTR_PE01), MP_ROM_PTR(&pin_PE01) },
// PDR_ON -----------------------------------------*/
// VDD --------------------------------------------*/
};
MP_DEFINE_CONST_DICT(mcu_pin_globals, mcu_pin_globals_table);

View File

@ -123,6 +123,9 @@ void EXTI4_IRQHandler(void) {
stm_exti_callback[4](4);
}
#ifdef STM32L4
#define PR PR1
#endif
void EXTI9_5_IRQHandler(void) {
uint32_t pending = EXTI->PR;
for (uint i = 5; i <= 9; i++) {
@ -140,5 +143,9 @@ void EXTI15_10_IRQHandler(void) {
}
}
}
#ifdef STM32L4
#undef PR
#endif
#endif

View File

@ -91,6 +91,13 @@ typedef struct {
// Foundation Lines
#ifdef STM32L4R5xx
#define HAS_DAC 1
#define HAS_TRNG 1
#define HAS_BASIC_TIM 1
#include "stm32l4/stm32l4r5xx/periph.h"
#endif
#ifdef STM32F405xx
#define HAS_DAC 1
#define HAS_TRNG 1

View File

@ -85,6 +85,9 @@ extern const mp_obj_type_t mcu_pin_type;
#ifdef STM32F412Zx
#include "stm32f4/stm32f412zx/pins.h"
#endif
#ifdef STM32L4R5xx
#include "stm32l4/stm32l4r5xx/pins.h"
#endif
#ifdef STM32F405xx
#include "stm32f4/stm32f405xx/pins.h"
#endif

View File

@ -0,0 +1,110 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
#include "stm32l4xx_hal.h"
#include "supervisor/shared/safe_mode.h"
#include <stdbool.h>
// L4 Series
#ifdef STM32L4R5xx
#include "stm32l4/stm32l4r5xx/clocks.h"
#else
#error Please add other MCUs here so that they are not silently ignored due to #define typos
#endif
#if BOARD_HAS_HIGH_SPEED_CRYSTAL
#error HSE support needs to be added for the L4 family.
#elif !BOARD_HAS_LOW_SPEED_CRYSTAL
#error LSE clock source required
#endif
void Error_Handler(void) {
for (;;) {
}
}
#define HAL_CHECK(x) if (x != HAL_OK) Error_Handler()
void stm32_peripherals_clocks_init(void) {
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
// Configure LSE Drive
HAL_PWR_EnableBkUpAccess();
__HAL_RCC_LSEDRIVE_CONFIG(RCC_LSEDRIVE_LOW);
__HAL_RCC_PWR_CLK_ENABLE();
/** Configure the main internal regulator output voltage
*/
if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST) != HAL_OK) {
Error_Handler();
}
/* Activate PLL with MSI , stabilizied via PLL by LSE */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_MSI;
RCC_OscInitStruct.MSIState = RCC_MSI_ON;
RCC_OscInitStruct.LSEState = RCC_LSE_ON;
RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11;
RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI;
RCC_OscInitStruct.PLL.PLLM = 6;
RCC_OscInitStruct.PLL.PLLN = 30;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV5;
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
HAL_CHECK(HAL_RCC_OscConfig(&RCC_OscInitStruct));
/* Enable MSI Auto-calibration through LSE */
HAL_RCCEx_EnableMSIPLLMode();
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
// Avoid overshoot and start with HCLK 60 MHz
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
HAL_CHECK(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3));
/* AHB prescaler divider at 1 as second step */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
HAL_CHECK(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5));
/* Select MSI output as USB clock source */
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB | RCC_PERIPHCLK_RTC | RCC_PERIPHCLK_ADC;
PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_MSI;
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
PeriphClkInitStruct.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK;
HAL_CHECK(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct));
}

View File

@ -0,0 +1,67 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
#include "stm32l4xx_hal.h"
// Chip: STM32L4R5
// Line Type: Foundation Line
// Speed: 120MHz (MAX)
// Defaults:
#ifndef CPY_CLK_VSCALE
#define CPY_CLK_VSCALE (PWR_REGULATOR_VOLTAGE_SCALE1_BOOST) // up to 120MHz
#endif
#ifndef CPY_CLK_PLLM
#define CPY_CLK_PLLM (12)
#endif
#ifndef CPY_CLK_PLLN
#define CPY_CLK_PLLN (60)
#endif
#ifndef CPY_CLK_PLLP
#define CPY_CLK_PLLP (RCC_PLLP_DIV2)
#endif
#ifndef CPY_CLK_PLLQ
#define CPY_CLK_PLLQ (2)
#endif
#ifndef CPY_CLK_AHBDIV
#define CPY_CLK_AHBDIV (RCC_SYSCLK_DIV1)
#endif
#ifndef CPY_CLK_APB1DIV
#define CPY_CLK_APB1DIV (RCC_HCLK_DIV1)
#endif
#ifndef CPY_CLK_APB2DIV
#define CPY_CLK_APB2DIV (RCC_HCLK_DIV1)
#endif
#ifndef CPY_CLK_FLASH_LATENCY
#define CPY_CLK_FLASH_LATENCY (FLASH_LATENCY_5)
#endif
#ifndef CPY_CLK_USB_USES_AUDIOPLL
#define CPY_CLK_USB_USES_AUDIOPLL (0)
#endif
#ifndef BOARD_HAS_HIGH_SPEED_CRYSTAL
#define BOARD_HAS_HIGH_SPEED_CRYSTAL (1)
#endif

View File

@ -0,0 +1,60 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
#include "peripherals/gpio.h"
#include "common-hal/microcontroller/Pin.h"
void stm32_peripherals_gpio_init(void) {
// Enable all GPIO for now
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
__HAL_RCC_GPIOE_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOG_CLK_ENABLE();
// These ports are not used on the Swan R5 but may need to be enabeld on other boards
// __HAL_RCC_GPIOH_CLK_ENABLE();
// __HAL_RCC_GPIOI_CLK_ENABLE();
// Never reset pins
never_reset_pin_number(2,14); // PC14 OSC32_IN
never_reset_pin_number(2,15); // PC15 OSC32_OUT
never_reset_pin_number(0,13); // PA13 SWDIO
never_reset_pin_number(0,14); // PA14 SWCLK
// never_reset_pin_number(0,15); //PA15 JTDI
// never_reset_pin_number(1,3); //PB3 JTDO
// never_reset_pin_number(1,4); //PB4 JTRST
// Port H is not included in GPIO port array
// never_reset_pin_number(5,0); //PH0 JTDO
// never_reset_pin_number(5,1); //PH1 JTRST
}
void stm32l4_peripherals_status_led(uint8_t led, uint8_t state) {
}

View File

@ -0,0 +1,283 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
#include "py/obj.h"
#include "py/mphal.h"
#include "peripherals/pins.h"
#include "peripherals/periph.h"
I2C_TypeDef *mcu_i2c_banks[I2C_BANK_ARRAY_LEN] = {I2C1, I2C2, I2C3, I2C4};
const mcu_periph_obj_t mcu_i2c_sda_list[I2C_SDA_ARRAY_LEN] = {
PERIPH(3, 4, &pin_PB04),
PERIPH(1, 4, &pin_PB07),
PERIPH(4, 5, &pin_PB07),
PERIPH(1, 4, &pin_PB09),
PERIPH(4, 3, &pin_PB11),
PERIPH(2, 4, &pin_PB11),
PERIPH(2, 4, &pin_PB14),
PERIPH(3, 4, &pin_PC01),
PERIPH(3, 6, &pin_PC09),
PERIPH(4, 4, &pin_PD13),
PERIPH(2, 4, &pin_PF00),
PERIPH(4, 4, &pin_PF15),
PERIPH(3, 4, &pin_PG08),
PERIPH(1, 4, &pin_PG13),
PERIPH(2, 4, &pin_PH05),
PERIPH(3, 4, &pin_PH08),
};
const mcu_periph_obj_t mcu_i2c_scl_list[I2C_SCL_ARRAY_LEN] = {
PERIPH(1, 4, &pin_PB06),
PERIPH(1, 4, &pin_PG14),
PERIPH(3, 4, &pin_PA07),
PERIPH(4, 5, &pin_PB06),
PERIPH(1, 4, &pin_PB08),
PERIPH(4, 3, &pin_PB10),
PERIPH(2, 4, &pin_PB10),
PERIPH(2, 4, &pin_PB13),
PERIPH(3, 4, &pin_PC00),
PERIPH(4, 4, &pin_PD12),
PERIPH(2, 4, &pin_PF01),
PERIPH(4, 4, &pin_PF14),
PERIPH(3, 4, &pin_PG07),
PERIPH(2, 4, &pin_PH04),
PERIPH(3, 4, &pin_PH07),
};
SPI_TypeDef *mcu_spi_banks[SPI_BANK_ARRAY_LEN] = {SPI1, SPI2, SPI3};
const mcu_periph_obj_t mcu_spi_sck_list[SPI_SCK_ARRAY_LEN] = {
PERIPH(1, 5, &pin_PA01),
PERIPH(1, 5, &pin_PA05),
PERIPH(2, 3, &pin_PA09),
PERIPH(1, 5, &pin_PB03),
PERIPH(3, 6, &pin_PB03),
PERIPH(2, 5, &pin_PB10),
PERIPH(2, 5, &pin_PB13),
PERIPH(3, 6, &pin_PC10),
PERIPH(2, 5, &pin_PD01),
PERIPH(2, 3, &pin_PD03),
PERIPH(1, 5, &pin_PE13),
PERIPH(1, 5, &pin_PG02),
PERIPH(3, 6, &pin_PG09),
PERIPH(2, 5, &pin_PI01),
};
const mcu_periph_obj_t mcu_spi_mosi_list[SPI_MOSI_ARRAY_LEN] = {
PERIPH(1, 5, &pin_PA07),
PERIPH(1, 5, &pin_PA12),
PERIPH(1, 5, &pin_PB05),
PERIPH(3, 6, &pin_PB05),
PERIPH(2, 5, &pin_PB15),
PERIPH(2, 3, &pin_PC01),
PERIPH(2, 5, &pin_PC03),
PERIPH(3, 6, &pin_PC12),
PERIPH(2, 5, &pin_PD04),
PERIPH(3, 5, &pin_PD06),
PERIPH(1, 5, &pin_PE15),
PERIPH(1, 5, &pin_PG04),
PERIPH(3, 6, &pin_PG11),
PERIPH(2, 5, &pin_PI03),
};
const mcu_periph_obj_t mcu_spi_miso_list[SPI_MISO_ARRAY_LEN] = {
PERIPH(1, 5, &pin_PA06),
PERIPH(1, 5, &pin_PA11),
PERIPH(1, 5, &pin_PB04),
PERIPH(3, 6, &pin_PB04),
PERIPH(2, 5, &pin_PB14),
PERIPH(2, 5, &pin_PC02),
PERIPH(3, 6, &pin_PC11),
PERIPH(2, 5, &pin_PD03),
PERIPH(1, 5, &pin_PE14),
PERIPH(1, 5, &pin_PG03),
PERIPH(3, 6, &pin_PG10),
PERIPH(2, 5, &pin_PI02),
};
const mcu_periph_obj_t mcu_spi_nss_list[SPI_NSS_ARRAY_LEN] = {
PERIPH(1, 5, &pin_PA04),
PERIPH(3, 6, &pin_PA04),
PERIPH(1, 5, &pin_PA15),
PERIPH(3, 6, &pin_PA15),
PERIPH(1, 5, &pin_PB00),
PERIPH(2, 5, &pin_PB09),
PERIPH(2, 5, &pin_PB12),
PERIPH(2, 5, &pin_PD00),
PERIPH(1, 5, &pin_PE12),
PERIPH(1, 5, &pin_PG05),
PERIPH(3, 6, &pin_PG12),
PERIPH(2, 5, &pin_PI00),
};
// todo - add LPUART?
USART_TypeDef *mcu_uart_banks[MAX_UART] = {USART1, USART2, USART3, UART4, UART5};
bool mcu_uart_has_usart[MAX_UART] = {true, true, true, false, false};
const mcu_periph_obj_t mcu_uart_tx_list[UART_TX_ARRAY_LEN] = {
PERIPH(4, 9, &pin_PA00),
PERIPH(2, 7, &pin_PA02),
PERIPH(1, 7, &pin_PA09),
PERIPH(1, 7, &pin_PB06),
PERIPH(3, 7, &pin_PB10),
PERIPH(3, 7, &pin_PC04),
PERIPH(3, 7, &pin_PC10),
PERIPH(4, 9, &pin_PC10),
PERIPH(5, 9, &pin_PC12),
PERIPH(2, 7, &pin_PD05),
PERIPH(3, 7, &pin_PD08),
PERIPH(1, 7, &pin_PG09),
};
const mcu_periph_obj_t mcu_uart_rx_list[UART_RX_ARRAY_LEN] = {
PERIPH(4, 9, &pin_PA01),
PERIPH(2, 7, &pin_PA03),
PERIPH(1, 7, &pin_PA10),
PERIPH(2, 3, &pin_PA15),
PERIPH(1, 7, &pin_PB07),
PERIPH(3, 7, &pin_PB11),
PERIPH(3, 7, &pin_PC05),
PERIPH(3, 7, &pin_PC11),
PERIPH(4, 9, &pin_PC11),
PERIPH(5, 9, &pin_PD02),
PERIPH(2, 7, &pin_PD06),
PERIPH(3, 7, &pin_PD09),
PERIPH(1, 7, &pin_PG10),
};
// Timers
// TIM6 and TIM7 are basic timers that are only used by DAC, and don't have pins
TIM_TypeDef *mcu_tim_banks[TIM_BANK_ARRAY_LEN] = {TIM1, TIM2, TIM3, TIM4, TIM5, NULL, NULL, TIM8, /*TIM9*/ NULL, NULL, NULL, NULL, NULL, NULL, TIM15, TIM16, TIM17};
const mcu_tim_pin_obj_t mcu_tim_pin_list[TIM_PIN_ARRAY_LEN] = {
TIM(2, 1, 1, &pin_PA00),
TIM(5, 2, 1, &pin_PA00),
TIM(2, 1, 2, &pin_PA01),
TIM(5, 2, 2, &pin_PA01),
TIM(2, 1, 3, &pin_PA02),
TIM(5, 2, 3, &pin_PA02),
TIM(15, 15, 1, &pin_PA02),
TIM(2, 1, 4, &pin_PA03),
TIM(5, 2, 4, &pin_PA03),
TIM(15, 15, 2, &pin_PA03),
TIM(2, 1, 1, &pin_PA05),
TIM(3, 2, 1, &pin_PA06),
TIM(16, 15, 1, &pin_PA06),
TIM(3, 2, 2, &pin_PA07),
// TIM(17, 15, 1, &pin_PA07), // peripheral indices are 1 based, stored 0-based with 4 bits available.
TIM(1, 1, 1, &pin_PA08),
TIM(1, 1, 2, &pin_PA09),
TIM(1, 1, 3, &pin_PA10),
TIM(1, 1, 4, &pin_PA11),
TIM(2, 1, 1, &pin_PA15),
TIM(3, 2, 3, &pin_PB00),
TIM(3, 2, 4, &pin_PB01),
TIM(2, 1, 2, &pin_PB03),
TIM(3, 2, 1, &pin_PB04),
TIM(3, 2, 2, &pin_PB05),
TIM(4, 2, 1, &pin_PB06),
TIM(4, 2, 2, &pin_PB07),
TIM(4, 2, 3, &pin_PB08),
TIM(16, 15, 1, &pin_PB08),
TIM(4, 2, 4, &pin_PB09),
// TIM(17, 15, 1, &pin_PB09), // peripheral indices are 1 based, stored 0-based with 4 bits available.
TIM(2, 1, 3, &pin_PB10),
TIM(2, 1, 4, &pin_PB11),
TIM(15, 15, 1, &pin_PB14),
TIM(15, 15, 2, &pin_PB15),
TIM(3, 2, 1, &pin_PC06),
TIM(8, 3, 1, &pin_PC06),
TIM(3, 2, 2, &pin_PC07),
TIM(8, 3, 2, &pin_PC07),
TIM(3, 2, 3, &pin_PC08),
TIM(8, 3, 3, &pin_PC08),
TIM(3, 2, 4, &pin_PC09),
TIM(8, 3, 4, &pin_PC09),
TIM(4, 2, 1, &pin_PD12),
TIM(4, 2, 2, &pin_PD13),
TIM(4, 2, 3, &pin_PD14),
TIM(4, 2, 4, &pin_PD15),
TIM(16, 15, 1, &pin_PE00),
// TIM(17, 15, 1, &pin_PE01), // peripheral indices are 1 based, stored 0-based with 4 bits available.
TIM(3, 2, 1, &pin_PE03),
TIM(3, 2, 2, &pin_PE04),
TIM(3, 2, 3, &pin_PE05),
TIM(3, 2, 4, &pin_PE06),
TIM(1, 1, 1, &pin_PE09),
TIM(1, 1, 2, &pin_PE11),
TIM(1, 1, 3, &pin_PE13),
TIM(1, 1, 4, &pin_PE14),
TIM(5, 2, 1, &pin_PF06),
TIM(5, 2, 2, &pin_PF07),
TIM(5, 2, 3, &pin_PF08),
TIM(5, 2, 4, &pin_PF09),
TIM(15, 15, 1, &pin_PF09),
TIM(15, 15, 2, &pin_PF10),
TIM(15, 15, 1, &pin_PG10),
TIM(15, 15, 2, &pin_PG11),
TIM(5, 2, 1, &pin_PH10),
TIM(5, 2, 2, &pin_PH11),
TIM(5, 2, 3, &pin_PH12),
TIM(5, 2, 4, &pin_PI00),
TIM(8, 3, 4, &pin_PI02),
TIM(8, 3, 1, &pin_PI05),
TIM(8, 3, 2, &pin_PI06),
TIM(8, 3, 3, &pin_PI07),
};
// SDIO
// SDIO_TypeDef *mcu_sdio_banks[1] = {SDIO};
// todo - the L4 has a SDMMC pripheral
const mcu_periph_obj_t mcu_sdio_clock_list[1] = {
PERIPH(1, 12, &pin_PC12),
};
const mcu_periph_obj_t mcu_sdio_command_list[1] = {
PERIPH(1, 12, &pin_PD02),
};
const mcu_periph_obj_t mcu_sdio_data0_list[1] = {
PERIPH(1, 12, &pin_PC08),
};
const mcu_periph_obj_t mcu_sdio_data1_list[1] = {
PERIPH(1, 12, &pin_PC09),
};
const mcu_periph_obj_t mcu_sdio_data2_list[1] = {
PERIPH(1, 12, &pin_PC10),
};
const mcu_periph_obj_t mcu_sdio_data3_list[1] = {
PERIPH(1, 12, &pin_PC11),
};
// CAN
CAN_TypeDef *mcu_can_banks[] = {CAN1};
const mcu_periph_obj_t mcu_can_tx_list[4] = {
PERIPH(1, 10, &pin_PA12),
PERIPH(1, 10, &pin_PB09),
PERIPH(1, 10, &pin_PD01),
PERIPH(1, 10, &pin_PH13),
};
const mcu_periph_obj_t mcu_can_rx_list[4] = {
PERIPH(1, 10, &pin_PA11),
PERIPH(1, 10, &pin_PB08),
PERIPH(1, 10, &pin_PD00),
PERIPH(1, 10, &pin_PI09),
};

View File

@ -0,0 +1,80 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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_STM32_PERIPHERALS_STM32L4R5XX_PERIPH_H
#define MICROPY_INCLUDED_STM32_PERIPHERALS_STM32L4R5XX_PERIPH_H
// I2C
#define I2C_BANK_ARRAY_LEN 4
#define I2C_SDA_ARRAY_LEN 16
#define I2C_SCL_ARRAY_LEN 15
extern I2C_TypeDef *mcu_i2c_banks[I2C_BANK_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_i2c_sda_list[I2C_SDA_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_i2c_scl_list[I2C_SCL_ARRAY_LEN];
// SPI
#define SPI_BANK_ARRAY_LEN 3
#define SPI_SCK_ARRAY_LEN 14
#define SPI_MOSI_ARRAY_LEN 14
#define SPI_MISO_ARRAY_LEN 12
#define SPI_NSS_ARRAY_LEN 12
extern SPI_TypeDef *mcu_spi_banks[SPI_BANK_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_spi_sck_list[SPI_SCK_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_spi_mosi_list[SPI_MOSI_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_spi_miso_list[SPI_MISO_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_spi_nss_list[SPI_NSS_ARRAY_LEN];
// UART
#define UART_TX_ARRAY_LEN 12
#define UART_RX_ARRAY_LEN 13
extern USART_TypeDef *mcu_uart_banks[MAX_UART];
extern bool mcu_uart_has_usart[MAX_UART];
extern const mcu_periph_obj_t mcu_uart_tx_list[UART_TX_ARRAY_LEN];
extern const mcu_periph_obj_t mcu_uart_rx_list[UART_RX_ARRAY_LEN];
// Timers
#define TIM_BANK_ARRAY_LEN 17
#define TIM_PIN_ARRAY_LEN (73 - 3)
extern TIM_TypeDef *mcu_tim_banks[TIM_BANK_ARRAY_LEN];
extern const mcu_tim_pin_obj_t mcu_tim_pin_list[TIM_PIN_ARRAY_LEN];
// SDIO
// extern SDIO_TypeDef *mcu_sdio_banks[1];
// extern const mcu_periph_obj_t mcu_sdio_clock_list[1];
// extern const mcu_periph_obj_t mcu_sdio_command_list[1];
// extern const mcu_periph_obj_t mcu_sdio_data0_list[1];
// extern const mcu_periph_obj_t mcu_sdio_data1_list[1];
// extern const mcu_periph_obj_t mcu_sdio_data2_list[1];
// extern const mcu_periph_obj_t mcu_sdio_data3_list[1];
// CAN
extern CAN_TypeDef *mcu_can_banks[1];
extern const mcu_periph_obj_t mcu_can_tx_list[4];
extern const mcu_periph_obj_t mcu_can_rx_list[4];
#endif // MICROPY_INCLUDED_STM32_PERIPHERALS_STM32L4R5XX_PERIPH_H

View File

@ -0,0 +1,172 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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.
*/
#include "py/obj.h"
#include "py/mphal.h"
#include "peripherals/pins.h"
#include STM32_HAL_H
const mcu_pin_obj_t pin_PA00 = PIN(0, 0, ADC_INPUT(ADC_1,5));
const mcu_pin_obj_t pin_PA01 = PIN(0, 1, ADC_INPUT(ADC_1,6));
const mcu_pin_obj_t pin_PA02 = PIN(0, 2, ADC_INPUT(ADC_1,7));
const mcu_pin_obj_t pin_PA03 = PIN(0, 3, ADC_INPUT(ADC_1,8));
const mcu_pin_obj_t pin_PA04 = PIN(0, 4, ADC_INPUT(ADC_1,9));
const mcu_pin_obj_t pin_PA05 = PIN(0, 5, ADC_INPUT(ADC_1,10));
const mcu_pin_obj_t pin_PA06 = PIN(0, 6, ADC_INPUT(ADC_1,11));
const mcu_pin_obj_t pin_PA07 = PIN(0, 7, ADC_INPUT(ADC_1,12));
const mcu_pin_obj_t pin_PA08 = PIN(0, 8, NO_ADC);
const mcu_pin_obj_t pin_PA09 = PIN(0, 9, NO_ADC);
const mcu_pin_obj_t pin_PA10 = PIN(0, 10, NO_ADC);
const mcu_pin_obj_t pin_PA11 = PIN(0, 11, NO_ADC);
const mcu_pin_obj_t pin_PA12 = PIN(0, 12, NO_ADC);
const mcu_pin_obj_t pin_PA13 = PIN(0, 13, NO_ADC);
const mcu_pin_obj_t pin_PA14 = PIN(0, 14, NO_ADC);
const mcu_pin_obj_t pin_PA15 = PIN(0, 15, NO_ADC);
const mcu_pin_obj_t pin_PB00 = PIN(1, 0, ADC_INPUT(ADC_1,15));
const mcu_pin_obj_t pin_PB01 = PIN(1, 1, ADC_INPUT(ADC_1,16));
const mcu_pin_obj_t pin_PB02 = PIN(1, 2, NO_ADC);
const mcu_pin_obj_t pin_PB03 = PIN(1, 3, NO_ADC);
const mcu_pin_obj_t pin_PB04 = PIN(1, 4, NO_ADC);
const mcu_pin_obj_t pin_PB05 = PIN(1, 5, NO_ADC);
const mcu_pin_obj_t pin_PB06 = PIN(1, 6, NO_ADC);
const mcu_pin_obj_t pin_PB07 = PIN(1, 7, NO_ADC);
const mcu_pin_obj_t pin_PB08 = PIN(1, 8, NO_ADC);
const mcu_pin_obj_t pin_PB09 = PIN(1, 9, NO_ADC);
const mcu_pin_obj_t pin_PB10 = PIN(1, 10, NO_ADC);
const mcu_pin_obj_t pin_PB11 = PIN(1, 11, NO_ADC);
const mcu_pin_obj_t pin_PB12 = PIN(1, 12, NO_ADC);
const mcu_pin_obj_t pin_PB13 = PIN(1, 13, NO_ADC);
const mcu_pin_obj_t pin_PB14 = PIN(1, 14, NO_ADC);
const mcu_pin_obj_t pin_PB15 = PIN(1, 15, NO_ADC);
const mcu_pin_obj_t pin_PC00 = PIN(2, 0, ADC_INPUT(ADC_1,1));
const mcu_pin_obj_t pin_PC01 = PIN(2, 1, ADC_INPUT(ADC_1,2));
const mcu_pin_obj_t pin_PC02 = PIN(2, 2, ADC_INPUT(ADC_1,3));
const mcu_pin_obj_t pin_PC03 = PIN(2, 3, ADC_INPUT(ADC_1,4));
const mcu_pin_obj_t pin_PC04 = PIN(2, 4, ADC_INPUT(ADC_1,13));
const mcu_pin_obj_t pin_PC05 = PIN(2, 5, ADC_INPUT(ADC_1,14));
const mcu_pin_obj_t pin_PC06 = PIN(2, 6, NO_ADC);
const mcu_pin_obj_t pin_PC07 = PIN(2, 7, NO_ADC);
const mcu_pin_obj_t pin_PC08 = PIN(2, 8, NO_ADC);
const mcu_pin_obj_t pin_PC09 = PIN(2, 9, NO_ADC);
const mcu_pin_obj_t pin_PC10 = PIN(2, 10, NO_ADC);
const mcu_pin_obj_t pin_PC11 = PIN(2, 11, NO_ADC);
const mcu_pin_obj_t pin_PC12 = PIN(2, 12, NO_ADC);
const mcu_pin_obj_t pin_PC13 = PIN(2, 13, NO_ADC);
const mcu_pin_obj_t pin_PC14 = PIN(2, 14, NO_ADC);
const mcu_pin_obj_t pin_PC15 = PIN(2, 15, NO_ADC);
const mcu_pin_obj_t pin_PD00 = PIN(3, 0, NO_ADC);
const mcu_pin_obj_t pin_PD01 = PIN(3, 1, NO_ADC);
const mcu_pin_obj_t pin_PD02 = PIN(3, 2, NO_ADC);
const mcu_pin_obj_t pin_PD03 = PIN(3, 3, NO_ADC);
const mcu_pin_obj_t pin_PD04 = PIN(3, 4, NO_ADC);
const mcu_pin_obj_t pin_PD05 = PIN(3, 5, NO_ADC);
const mcu_pin_obj_t pin_PD06 = PIN(3, 6, NO_ADC);
const mcu_pin_obj_t pin_PD07 = PIN(3, 7, NO_ADC);
const mcu_pin_obj_t pin_PD08 = PIN(3, 8, NO_ADC);
const mcu_pin_obj_t pin_PD09 = PIN(3, 9, NO_ADC);
const mcu_pin_obj_t pin_PD10 = PIN(3, 10, NO_ADC);
const mcu_pin_obj_t pin_PD11 = PIN(3, 11, NO_ADC);
const mcu_pin_obj_t pin_PD12 = PIN(3, 12, NO_ADC);
const mcu_pin_obj_t pin_PD13 = PIN(3, 13, NO_ADC);
const mcu_pin_obj_t pin_PD14 = PIN(3, 14, NO_ADC);
const mcu_pin_obj_t pin_PD15 = PIN(3, 15, NO_ADC);
const mcu_pin_obj_t pin_PE00 = PIN(4, 0, NO_ADC);
const mcu_pin_obj_t pin_PE01 = PIN(4, 1, NO_ADC);
const mcu_pin_obj_t pin_PE02 = PIN(4, 2, NO_ADC);
const mcu_pin_obj_t pin_PE03 = PIN(4, 3, NO_ADC);
const mcu_pin_obj_t pin_PE04 = PIN(4, 4, NO_ADC);
const mcu_pin_obj_t pin_PE05 = PIN(4, 5, NO_ADC);
const mcu_pin_obj_t pin_PE06 = PIN(4, 6, NO_ADC);
const mcu_pin_obj_t pin_PE07 = PIN(4, 7, NO_ADC);
const mcu_pin_obj_t pin_PE08 = PIN(4, 8, NO_ADC);
const mcu_pin_obj_t pin_PE09 = PIN(4, 9, NO_ADC);
const mcu_pin_obj_t pin_PE10 = PIN(4, 10, NO_ADC);
const mcu_pin_obj_t pin_PE11 = PIN(4, 11, NO_ADC);
const mcu_pin_obj_t pin_PE12 = PIN(4, 12, NO_ADC);
const mcu_pin_obj_t pin_PE13 = PIN(4, 13, NO_ADC);
const mcu_pin_obj_t pin_PE14 = PIN(4, 14, NO_ADC);
const mcu_pin_obj_t pin_PE15 = PIN(4, 15, NO_ADC);
const mcu_pin_obj_t pin_PF00 = PIN(5, 0, NO_ADC);
const mcu_pin_obj_t pin_PF01 = PIN(5, 1, NO_ADC);
const mcu_pin_obj_t pin_PF02 = PIN(5, 2, NO_ADC);
const mcu_pin_obj_t pin_PF03 = PIN(5, 3, NO_ADC);
const mcu_pin_obj_t pin_PF04 = PIN(5, 4, NO_ADC);
const mcu_pin_obj_t pin_PF05 = PIN(5, 5, NO_ADC);
const mcu_pin_obj_t pin_PF06 = PIN(5, 6, NO_ADC);
const mcu_pin_obj_t pin_PF07 = PIN(5, 7, NO_ADC);
const mcu_pin_obj_t pin_PF08 = PIN(5, 8, NO_ADC);
const mcu_pin_obj_t pin_PF09 = PIN(5, 9, NO_ADC);
const mcu_pin_obj_t pin_PF10 = PIN(5, 10, NO_ADC);
const mcu_pin_obj_t pin_PF11 = PIN(5, 11, NO_ADC);
const mcu_pin_obj_t pin_PF12 = PIN(5, 12, NO_ADC);
const mcu_pin_obj_t pin_PF13 = PIN(5, 13, NO_ADC);
const mcu_pin_obj_t pin_PF14 = PIN(5, 14, NO_ADC);
const mcu_pin_obj_t pin_PF15 = PIN(5, 15, NO_ADC);
const mcu_pin_obj_t pin_PG00 = PIN(6, 0, NO_ADC);
const mcu_pin_obj_t pin_PG01 = PIN(6, 1, NO_ADC);
const mcu_pin_obj_t pin_PG02 = PIN(6, 2, NO_ADC);
const mcu_pin_obj_t pin_PG03 = PIN(6, 3, NO_ADC);
const mcu_pin_obj_t pin_PG04 = PIN(6, 4, NO_ADC);
const mcu_pin_obj_t pin_PG05 = PIN(6, 5, NO_ADC);
const mcu_pin_obj_t pin_PG06 = PIN(6, 6, NO_ADC);
const mcu_pin_obj_t pin_PG07 = PIN(6, 7, NO_ADC);
const mcu_pin_obj_t pin_PG08 = PIN(6, 8, NO_ADC);
const mcu_pin_obj_t pin_PG09 = PIN(6, 9, NO_ADC);
const mcu_pin_obj_t pin_PG10 = PIN(6, 10, NO_ADC);
const mcu_pin_obj_t pin_PG11 = PIN(6, 11, NO_ADC);
const mcu_pin_obj_t pin_PG12 = PIN(6, 12, NO_ADC);
const mcu_pin_obj_t pin_PG13 = PIN(6, 13, NO_ADC);
const mcu_pin_obj_t pin_PG14 = PIN(6, 14, NO_ADC);
const mcu_pin_obj_t pin_PG15 = PIN(6, 15, NO_ADC);
const mcu_pin_obj_t pin_PH00 = PIN(7, 0, NO_ADC);
const mcu_pin_obj_t pin_PH01 = PIN(7, 1, NO_ADC);
const mcu_pin_obj_t pin_PH02 = PIN(7, 2, NO_ADC);
const mcu_pin_obj_t pin_PH03 = PIN(7, 3, NO_ADC);
const mcu_pin_obj_t pin_PH04 = PIN(7, 4, NO_ADC);
const mcu_pin_obj_t pin_PH05 = PIN(7, 5, NO_ADC);
const mcu_pin_obj_t pin_PH06 = PIN(7, 6, NO_ADC);
const mcu_pin_obj_t pin_PH07 = PIN(7, 7, NO_ADC);
const mcu_pin_obj_t pin_PH08 = PIN(7, 8, NO_ADC);
const mcu_pin_obj_t pin_PH09 = PIN(7, 9, NO_ADC);
const mcu_pin_obj_t pin_PH10 = PIN(7, 10, NO_ADC);
const mcu_pin_obj_t pin_PH11 = PIN(7, 11, NO_ADC);
const mcu_pin_obj_t pin_PH12 = PIN(7, 12, NO_ADC);
const mcu_pin_obj_t pin_PH13 = PIN(7, 13, NO_ADC);
const mcu_pin_obj_t pin_PH14 = PIN(7, 14, NO_ADC);
const mcu_pin_obj_t pin_PH15 = PIN(7, 15, NO_ADC);
const mcu_pin_obj_t pin_PI00 = PIN(8, 0, NO_ADC);
const mcu_pin_obj_t pin_PI01 = PIN(8, 1, NO_ADC);
const mcu_pin_obj_t pin_PI02 = PIN(8, 2, NO_ADC);
const mcu_pin_obj_t pin_PI03 = PIN(8, 3, NO_ADC);
const mcu_pin_obj_t pin_PI04 = PIN(8, 4, NO_ADC);
const mcu_pin_obj_t pin_PI05 = PIN(8, 5, NO_ADC);
const mcu_pin_obj_t pin_PI06 = PIN(8, 6, NO_ADC);
const mcu_pin_obj_t pin_PI07 = PIN(8, 7, NO_ADC);
const mcu_pin_obj_t pin_PI08 = PIN(8, 8, NO_ADC);
const mcu_pin_obj_t pin_PI09 = PIN(8, 9, NO_ADC);
const mcu_pin_obj_t pin_PI10 = PIN(8, 10, NO_ADC);
const mcu_pin_obj_t pin_PI11 = PIN(8, 11, NO_ADC);

View File

@ -0,0 +1,171 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2021 Blues Wireless Contributors
*
* 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_STM32_PERIPHERALS_STM32L4R5XX_PINS_H
#define MICROPY_INCLUDED_STM32_PERIPHERALS_STM32L4R5XX_PINS_H
extern const mcu_pin_obj_t pin_PA00;
extern const mcu_pin_obj_t pin_PA01;
extern const mcu_pin_obj_t pin_PA02;
extern const mcu_pin_obj_t pin_PA03;
extern const mcu_pin_obj_t pin_PA04;
extern const mcu_pin_obj_t pin_PA05;
extern const mcu_pin_obj_t pin_PA06;
extern const mcu_pin_obj_t pin_PA07;
extern const mcu_pin_obj_t pin_PA08;
extern const mcu_pin_obj_t pin_PA09;
extern const mcu_pin_obj_t pin_PA10;
extern const mcu_pin_obj_t pin_PA11;
extern const mcu_pin_obj_t pin_PA12;
extern const mcu_pin_obj_t pin_PA13;
extern const mcu_pin_obj_t pin_PA14;
extern const mcu_pin_obj_t pin_PA15;
extern const mcu_pin_obj_t pin_PB00;
extern const mcu_pin_obj_t pin_PB01;
extern const mcu_pin_obj_t pin_PB02;
extern const mcu_pin_obj_t pin_PB03;
extern const mcu_pin_obj_t pin_PB04;
extern const mcu_pin_obj_t pin_PB05;
extern const mcu_pin_obj_t pin_PB06;
extern const mcu_pin_obj_t pin_PB07;
extern const mcu_pin_obj_t pin_PB08;
extern const mcu_pin_obj_t pin_PB09;
extern const mcu_pin_obj_t pin_PB10;
extern const mcu_pin_obj_t pin_PB11;
extern const mcu_pin_obj_t pin_PB12;
extern const mcu_pin_obj_t pin_PB13;
extern const mcu_pin_obj_t pin_PB14;
extern const mcu_pin_obj_t pin_PB15;
extern const mcu_pin_obj_t pin_PC00;
extern const mcu_pin_obj_t pin_PC01;
extern const mcu_pin_obj_t pin_PC02;
extern const mcu_pin_obj_t pin_PC03;
extern const mcu_pin_obj_t pin_PC04;
extern const mcu_pin_obj_t pin_PC05;
extern const mcu_pin_obj_t pin_PC06;
extern const mcu_pin_obj_t pin_PC07;
extern const mcu_pin_obj_t pin_PC08;
extern const mcu_pin_obj_t pin_PC09;
extern const mcu_pin_obj_t pin_PC10;
extern const mcu_pin_obj_t pin_PC11;
extern const mcu_pin_obj_t pin_PC12;
extern const mcu_pin_obj_t pin_PC13;
extern const mcu_pin_obj_t pin_PC14;
extern const mcu_pin_obj_t pin_PC15;
extern const mcu_pin_obj_t pin_PD00;
extern const mcu_pin_obj_t pin_PD01;
extern const mcu_pin_obj_t pin_PD02;
extern const mcu_pin_obj_t pin_PD03;
extern const mcu_pin_obj_t pin_PD04;
extern const mcu_pin_obj_t pin_PD05;
extern const mcu_pin_obj_t pin_PD06;
extern const mcu_pin_obj_t pin_PD07;
extern const mcu_pin_obj_t pin_PD08;
extern const mcu_pin_obj_t pin_PD09;
extern const mcu_pin_obj_t pin_PD10;
extern const mcu_pin_obj_t pin_PD11;
extern const mcu_pin_obj_t pin_PD12;
extern const mcu_pin_obj_t pin_PD13;
extern const mcu_pin_obj_t pin_PD14;
extern const mcu_pin_obj_t pin_PD15;
extern const mcu_pin_obj_t pin_PE00;
extern const mcu_pin_obj_t pin_PE01;
extern const mcu_pin_obj_t pin_PE02;
extern const mcu_pin_obj_t pin_PE03;
extern const mcu_pin_obj_t pin_PE04;
extern const mcu_pin_obj_t pin_PE05;
extern const mcu_pin_obj_t pin_PE06;
extern const mcu_pin_obj_t pin_PE07;
extern const mcu_pin_obj_t pin_PE08;
extern const mcu_pin_obj_t pin_PE09;
extern const mcu_pin_obj_t pin_PE10;
extern const mcu_pin_obj_t pin_PE11;
extern const mcu_pin_obj_t pin_PE12;
extern const mcu_pin_obj_t pin_PE13;
extern const mcu_pin_obj_t pin_PE14;
extern const mcu_pin_obj_t pin_PE15;
extern const mcu_pin_obj_t pin_PF00;
extern const mcu_pin_obj_t pin_PF01;
extern const mcu_pin_obj_t pin_PF02;
extern const mcu_pin_obj_t pin_PF03;
extern const mcu_pin_obj_t pin_PF04;
extern const mcu_pin_obj_t pin_PF05;
extern const mcu_pin_obj_t pin_PF06;
extern const mcu_pin_obj_t pin_PF07;
extern const mcu_pin_obj_t pin_PF08;
extern const mcu_pin_obj_t pin_PF09;
extern const mcu_pin_obj_t pin_PF10;
extern const mcu_pin_obj_t pin_PF11;
extern const mcu_pin_obj_t pin_PF12;
extern const mcu_pin_obj_t pin_PF13;
extern const mcu_pin_obj_t pin_PF14;
extern const mcu_pin_obj_t pin_PF15;
extern const mcu_pin_obj_t pin_PG00;
extern const mcu_pin_obj_t pin_PG01;
extern const mcu_pin_obj_t pin_PG02;
extern const mcu_pin_obj_t pin_PG03;
extern const mcu_pin_obj_t pin_PG04;
extern const mcu_pin_obj_t pin_PG05;
extern const mcu_pin_obj_t pin_PG06;
extern const mcu_pin_obj_t pin_PG07;
extern const mcu_pin_obj_t pin_PG08;
extern const mcu_pin_obj_t pin_PG09;
extern const mcu_pin_obj_t pin_PG10;
extern const mcu_pin_obj_t pin_PG11;
extern const mcu_pin_obj_t pin_PG12;
extern const mcu_pin_obj_t pin_PG13;
extern const mcu_pin_obj_t pin_PG14;
extern const mcu_pin_obj_t pin_PG15;
extern const mcu_pin_obj_t pin_PH00;
extern const mcu_pin_obj_t pin_PH01;
extern const mcu_pin_obj_t pin_PH02;
extern const mcu_pin_obj_t pin_PH03;
extern const mcu_pin_obj_t pin_PH04;
extern const mcu_pin_obj_t pin_PH05;
extern const mcu_pin_obj_t pin_PH06;
extern const mcu_pin_obj_t pin_PH07;
extern const mcu_pin_obj_t pin_PH08;
extern const mcu_pin_obj_t pin_PH09;
extern const mcu_pin_obj_t pin_PH10;
extern const mcu_pin_obj_t pin_PH11;
extern const mcu_pin_obj_t pin_PH12;
extern const mcu_pin_obj_t pin_PH13;
extern const mcu_pin_obj_t pin_PH14;
extern const mcu_pin_obj_t pin_PH15;
extern const mcu_pin_obj_t pin_PI00;
extern const mcu_pin_obj_t pin_PI01;
extern const mcu_pin_obj_t pin_PI02;
extern const mcu_pin_obj_t pin_PI03;
extern const mcu_pin_obj_t pin_PI04;
extern const mcu_pin_obj_t pin_PI05;
extern const mcu_pin_obj_t pin_PI06;
extern const mcu_pin_obj_t pin_PI07;
extern const mcu_pin_obj_t pin_PI08;
extern const mcu_pin_obj_t pin_PI09;
extern const mcu_pin_obj_t pin_PI10;
extern const mcu_pin_obj_t pin_PI11;
#endif // MICROPY_INCLUDED_STM32_PERIPHERALS_STM32L4R5XX_PINS_H

View File

@ -122,17 +122,29 @@ static size_t irq_map[] = {
NULL_IRQ,
#endif
#ifdef TIM15
#ifdef STM32L4
TIM1_BRK_TIM15_IRQn,
#else
TIM15_IRQn,
#endif
#else
NULL_IRQ,
#endif
#ifdef TIM16
#ifdef STM32L4
TIM1_UP_TIM16_IRQn,
#else
TIM16_IRQn,
#endif
#else
NULL_IRQ,
#endif
#ifdef TIM17
#ifdef STM32L4
TIM1_TRG_COM_TIM17_IRQn
#else
TIM17_IRQn,
#endif
#else
NULL_IRQ,
#endif

View File

@ -94,6 +94,16 @@ STATIC const flash_layout_t flash_layout[] = {
};
STATIC uint8_t _flash_cache[0x20000] __attribute__((aligned(4)));
#elif defined(STM32L4)
// todo - the L4 devices can have different flash sizes and different page sizes
// depending upon the dual bank configuration
// This is hardcoded for the Swan R5. When support for other devices is needed more conditionals will be required
// to differentiate.
STATIC const flash_layout_t flash_layout[] = {
{ 0x08000000, 0x1000, 256 },
};
STATIC uint8_t _flash_cache[0x1000] __attribute__((aligned(4)));
#else
#error Unsupported processor
#endif
@ -125,10 +135,23 @@ STATIC uint32_t get_bank(uint32_t addr) {
}
#endif
// Return the sector of a given flash address.
uint32_t flash_get_sector_info(uint32_t addr, uint32_t *start_addr, uint32_t *size) {
if (addr >= flash_layout[0].base_address) {
uint32_t sector_index = 0;
if (MP_ARRAY_SIZE(flash_layout) == 1) {
sector_index = (addr - flash_layout[0].base_address) / flash_layout[0].sector_size;
if (sector_index >= flash_layout[0].sector_count) {
return 0;
}
if (start_addr) {
*start_addr = flash_layout[0].base_address + (sector_index * flash_layout[0].sector_size);
}
if (size) {
*size = flash_layout[0].sector_size;
}
return sector_index;
}
for (uint8_t i = 0; i < MP_ARRAY_SIZE(flash_layout); ++i) {
for (uint8_t j = 0; j < flash_layout[i].sector_count; ++j) {
uint32_t sector_start_next = flash_layout[i].base_address
@ -147,7 +170,7 @@ uint32_t flash_get_sector_info(uint32_t addr, uint32_t *start_addr, uint32_t *si
}
}
}
return 0;
return 0; // todo dangerous - shouldn't this raise an exception?
}
void supervisor_flash_init(void) {
@ -169,22 +192,34 @@ void port_internal_flash_flush(void) {
#if defined(STM32H7)
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS_BANK1 | FLASH_FLAG_ALL_ERRORS_BANK2);
#else
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |
FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
#ifndef FLASH_FLAG_ALL_ERRORS
#define FLASH_FLAG_ALL_ERRORS FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR
#endif
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS);
#endif
// set up for erase
FLASH_EraseInitTypeDef EraseInitStruct;
FLASH_EraseInitTypeDef EraseInitStruct = {};
#if CPY_STM32L4
EraseInitStruct.TypeErase = TYPEERASE_PAGES;
EraseInitStruct.Banks = FLASH_BANK_1;
#else
EraseInitStruct.TypeErase = TYPEERASE_SECTORS;
EraseInitStruct.VoltageRange = VOLTAGE_RANGE_3; // voltage range needs to be 2.7V to 3.6V
#endif
// get the sector information
uint32_t sector_size;
uint32_t sector_start_addr = 0xffffffff;
#if defined(STM32H7)
EraseInitStruct.Banks = get_bank(_cache_flash_addr);
#endif
#if CPY_STM32L4
EraseInitStruct.Page = flash_get_sector_info(_cache_flash_addr, &sector_start_addr, &sector_size);
EraseInitStruct.NbPages = 1;
#else
EraseInitStruct.Sector = flash_get_sector_info(_cache_flash_addr, &sector_start_addr, &sector_size);
EraseInitStruct.NbSectors = 1;
#endif
if (sector_size > sizeof(_flash_cache) || sector_start_addr == 0xffffffff) {
reset_into_safe_mode(FLASH_WRITE_FAIL);
}
@ -217,6 +252,19 @@ void port_internal_flash_flush(void) {
cache_addr += 8;
sector_start_addr += 32;
}
#elif CPY_STM32L4
// program the flash word by word
for (uint32_t i = 0; i < sector_size / 8; i++) {
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD, sector_start_addr,
*(uint64_t *)cache_addr) != HAL_OK) {
// error occurred during flash write
HAL_FLASH_Lock(); // lock the flash
reset_into_safe_mode(FLASH_WRITE_FAIL);
}
// RAM memory is by word (4 byte), but flash memory is by byte
cache_addr += 2;
sector_start_addr += 8;
}
#else // STM32F4
// program the flash word by word
@ -236,6 +284,7 @@ void port_internal_flash_flush(void) {
// lock the flash
HAL_FLASH_Lock();
}
}
static uint32_t convert_block_to_flash_addr(uint32_t block) {

View File

@ -86,6 +86,12 @@
#define INTERNAL_FLASH_FILESYSTEM_START_ADDR 0x08020000
#endif
#ifdef STM32L4R5xx
#define STM32_FLASH_SIZE 0x100000 // 1MB // for now just use the first bank
#define INTERNAL_FLASH_FILESYSTEM_SIZE 0x20000 // 128KiB
#define INTERNAL_FLASH_FILESYSTEM_START_ADDR 0x080e0000
#endif
#define INTERNAL_FLASH_FILESYSTEM_NUM_BLOCKS (INTERNAL_FLASH_FILESYSTEM_SIZE / FILESYSTEM_BLOCK_SIZE)
#define STM32_FLASH_OFFSET 0x8000000 // All STM32 chips map to this flash location

View File

@ -177,7 +177,7 @@ safe_mode_t port_init(void) {
HAL_Init(); // Turns on SysTick
__HAL_RCC_SYSCFG_CLK_ENABLE();
#if CPY_STM32F4
#if CPY_STM32F4 || CPY_STM32L4
__HAL_RCC_PWR_CLK_ENABLE();
HAL_PWR_EnableBkUpAccess();

View File

@ -43,6 +43,11 @@ STATIC void init_usb_vbus_sense(void) {
// Deactivate VBUS Sensing B
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN;
#if (BOARD_NO_USB_OTG_ID_SENSE)
USB_OTG_FS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD;
USB_OTG_FS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD;
#endif
// B-peripheral session valid override enable
USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN;
USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL;
@ -63,6 +68,12 @@ STATIC void init_usb_vbus_sense(void) {
}
void init_usb_hardware(void) {
/* Enable USB power on Pwrctrl CR2 register */
#ifdef PWR_CR2_USV
HAL_PWREx_EnableVddUSB();
#endif
// TODO: if future chips overload this with options, move to peripherals management.
GPIO_InitTypeDef GPIO_InitStruct = {0};
@ -80,7 +91,7 @@ void init_usb_hardware(void) {
GPIO_InitStruct.Pull = GPIO_NOPULL;
#if CPY_STM32H7
GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS;
#elif CPY_STM32F4 || CPY_STM32F7
#elif CPY_STM32F4 || CPY_STM32F7 || CPY_STM32L4
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
#endif
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
@ -100,18 +111,20 @@ void init_usb_hardware(void) {
#endif
/* This for ID line debug */
#if !(BOARD_NO_USB_OTG_ID_SENSE)
GPIO_InitStruct.Pin = GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
#if CPY_STM32H7
GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS;
#elif CPY_STM32F4 || CPY_STM32F7
#elif CPY_STM32F4 || CPY_STM32F7 || CPY_STM32L4
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
#endif
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
never_reset_pin_number(0, 10);
claim_pin(0, 10);
#endif
#ifdef STM32F412Zx
/* Configure POWER_SWITCH IO pin (F412 ONLY)*/
@ -131,6 +144,7 @@ void init_usb_hardware(void) {
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
#endif
init_usb_vbus_sense();
}

View File

@ -1,142 +1,142 @@
Port,,AF0,AF1,AF2,AF3,AF4,AF5,AF6,AF7,AF8,AF9,AF10,AF11,AF12,AF13,AF14,AF15,
,,SYS,TIM1/2,TIM3/4/5,TIM8/9/10/11,I2C1/2/3,SPI1/SPI2/I2S2/I2S2ext,SPI3/I2Sext/I2S3,USART1/2/3/I2S3ext,UART4/5/USART6,CAN1/CAN2/TIM12/13/14,OTG_FS/OTG_HS,ETH,FSMC/SDIO/OTG_FS,DCMI,,,ADC
PortA,PA0,,TIM2_CH1/TIM2_ETR,TIM5_CH1,TIM8_ETR,,,,USART2_CTS,UART4_TX,,,ETH_MII_CRS,,,,EVENTOUT,ADC123_IN0
PortA,PA1,,TIM2_CH2,TIM5_CH2,,,,,USART2_RTS,UART4_RX,,,ETH_MII_RX_CLK/ETH_RMII_REF_CLK,,,,EVENTOUT,ADC123_IN1
PortA,PA2,,TIM2_CH3,TIM5_CH3,TIM9_CH1,,,,USART2_TX,,,,ETH_MDIO,,,,EVENTOUT,ADC123_IN2
PortA,PA3,,TIM2_CH4,TIM5_CH4,TIM9_CH2,,,,USART2_RX,,,OTG_HS_ULPI_D0,ETH_MII_COL,,,,EVENTOUT,ADC123_IN3
PortA,PA4,,,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_CK,,,,,OTG_HS_SOF,DCMI_HSYNC,,EVENTOUT,ADC12_IN4
PortA,PA5,,TIM2_CH1/TIM2_ETR,,TIM8_CH1N,,SPI1_SCK,,,,,OTG_HS_ULPI_CK,,,,,EVENTOUT,ADC12_IN5
PortA,PA6,,TIM1_BKIN,TIM3_CH1,TIM8_BKIN,,SPI1_MISO,,,,TIM13_CH1,,,,DCMI_PIXCK,,EVENTOUT,ADC12_IN6
PortA,PA7,,TIM1_CH1N,TIM3_CH2,TIM8_CH1N,,SPI1_MOSI,,,,TIM14_CH1,,ETH_MII_RX_DV/ETH_RMII_CRS_DV,,,,EVENTOUT,ADC12_IN7
PortA,PA8,MCO1,TIM1_CH1,,,I2C3_SCL,,,USART1_CK,,,OTG_FS_SOF,,,,,EVENTOUT,
PortA,PA9,,TIM1_CH2,,,I2C3_SMBA,,,USART1_TX,,,,,,DCMI_D0,,EVENTOUT,
PortA,PA10,,TIM1_CH3,,,,,,USART1_RX,,,OTG_FS_ID,,,DCMI_D1,,EVENTOUT,
PortA,PA11,,TIM1_CH4,,,,,,USART1_CTS,,CAN1_RX,OTG_FS_DM,,,,,EVENTOUT,
PortA,PA12,,TIM1_ETR,,,,,,USART1_RTS,,CAN1_TX,OTG_FS_DP,,,,,EVENTOUT,
PortA,PA13,JTMS/SWDIO,,,,,,,,,,,,,,,EVENTOUT,
PortA,PA14,JTCK/SWCLK,,,,,,,,,,,,,,,EVENTOUT,
PortA,PA15,JTDI,TIM2_CH1/TIM2_ETR,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,,,,,,,,,EVENTOUT,
PortB,PB0,,TIM1_CH2N,TIM3_CH3,TIM8_CH2N,,,,,,,OTG_HS_ULPI_D1,ETH_MII_RXD2,,,,EVENTOUT,ADC12_IN8
PortB,PB1,,TIM1_CH3N,TIM3_CH4,TIM8_CH3N,,,,,,,OTG_HS_ULPI_D2,ETH_MII_RXD3,,,,EVENTOUT,ADC12_IN9
PortB,PB2,,,,,,,,,,,,,,,,EVENTOUT,
PortB,PB3,JTDO/TRACESWO,TIM2_CH2,,,,SPI1_SCK,SPI3_SCK/I2S3_CK,,,,,,,,,EVENTOUT,
PortB,PB4,NJTRST,,TIM3_CH1,,,SPI1_MISO,SPI3_MISO,I2S3ext_SD,,,,,,,,EVENTOUT,
PortB,PB5,,,TIM3_CH2,,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI/I2S3_SD,,,CAN2_RX,OTG_HS_ULPI_D7,ETH_PPS_OUT,,DCMI_D10,,EVENTOUT,
PortB,PB6,,,TIM4_CH1,,I2C1_SCL,,,USART1_TX,,CAN2_TX,,,,DCMI_D5,,EVENTOUT,
PortB,PB7,,,TIM4_CH2,,I2C1_SDA,,,USART1_RX,,,,,FSMC_NL,DCMI_VSYNC,,EVENTOUT,
PortB,PB8,,,TIM4_CH3,TIM10_CH1,I2C1_SCL,,,,,CAN1_RX,,ETH_MII_TXD3,SDIO_D4,DCMI_D6,,EVENTOUT,
PortB,PB9,,,TIM4_CH4,TIM11_CH1,I2C1_SDA,SPI2_NSS/I2S2_WS,,,,CAN1_TX,,,SDIO_D5,DCMI_D7,,EVENTOUT,
PortB,PB10,,TIM2_CH3,,,I2C2_SCL,SPI2_SCK/I2S2_CK,,USART3_TX,,,OTG_HS_ULPI_D3,ETH_MII_RX_ER,,,,EVENTOUT,
PortB,PB11,,TIM2_CH4,,,I2C2_SDA,,,USART3_RX,,,OTG_HS_ULPI_D4,ETH_MII_TX_EN/ETH_RMII_TX_EN,,,,EVENTOUT,
PortB,PB12,,TIM1_BKIN,,,I2C2_SMBA,SPI2_NSS/I2S2_WS,,USART3_CK,,CAN2_RX,OTG_HS_ULPI_D5,ETH_MII_TXD0/ETH_RMII_TXD0,OTG_HS_ID,,,EVENTOUT,
PortB,PB13,,TIM1_CH1N,,,,SPI2_SCK/I2S2_CK,,USART3_CTS,,CAN2_TX,OTG_HS_ULPI_D6,ETH_MII_TXD1/ETH_RMII_TXD1,,,,EVENTOUT,
PortB,PB14,,TIM1_CH2N,,TIM8_CH2N,,SPI2_MISO,I2S2ext_SD,USART3_RTS,,TIM12_CH1,,,OTG_HS_DM,,,EVENTOUT,
PortB,PB15,RTC_REFIN,TIM1_CH3N,,TIM8_CH3N,,SPI2_MOSI/I2S2_SD,,,,TIM12_CH2,,,OTG_HS_DP,,,EVENTOUT,
PortC,PC0,,,,,,,,,,,OTG_HS_ULPI_STP,,,,,EVENTOUT,ADC123_IN10
PortC,PC1,,,,,,,,,,,,ETH_MDC,,,,EVENTOUT,ADC123_IN11
PortC,PC2,,,,,,SPI2_MISO,I2S2ext_SD,,,,OTG_HS_ULPI_DIR,ETH_MII_TXD2,,,,EVENTOUT,ADC123_IN12
PortC,PC3,,,,,,SPI2_MOSI/I2S2_SD,,,,,OTG_HS_ULPI_NXT,ETH_MII_TX_CLK,,,,EVENTOUT,ADC123_IN13
PortC,PC4,,,,,,,,,,,,ETH_MII_RXD0/ETH_RMII_RXD0,,,,EVENTOUT,ADC123_IN14
PortC,PC5,,,,,,,,,,,,ETH_MII_RXD1/ETH_RMII_RXD1,,,,EVENTOUT,ADC123_IN15
PortC,PC6,,,TIM3_CH1,TIM8_CH1,,I2S2_MCK,,,USART6_TX,,,,SDIO_D6,DCMI_D0,,EVENTOUT,
PortC,PC7,,,TIM3_CH2,TIM8_CH2,,,I2S3_MCK,,USART6_RX,,,,SDIO_D7,DCMI_D1,,EVENTOUT,
PortC,PC8,,,TIM3_CH3,TIM8_CH3,,,,,USART6_CK,,,,SDIO_D0,DCMI_D2,,EVENTOUT,
PortC,PC9,MCO2,,TIM3_CH4,TIM8_CH4,I2C3_SDA,I2S_CKIN,,,,,,,SDIO_D1,DCMI_D3,,EVENTOUT,
PortC,PC10,,,,,,,SPI3_SCK/I2S3_CK,USART3_TX,UART4_TX,,,,SDIO_D2,DCMI_D8,,EVENTOUT,
PortC,PC11,,,,,,I2S3ext_SD,SPI3_MISO,USART3_RX,UART4_RX,,,,SDIO_D3,DCMI_D4,,EVENTOUT,
PortC,PC12,,,,,,,SPI3_MOSI/I2S3_SD,USART3_CK,UART5_TX,,,,SDIO_CK,DCMI_D9,,EVENTOUT,
PortC,PC13,,,,,,,,,,,,,,,,EVENTOUT,
PortC,PC14,,,,,,,,,,,,,,,,EVENTOUT,
PortC,PC15,,,,,,,,,,,,,,,,EVENTOUT,
PortD,PD0,,,,,,,,,,CAN1_RX,,,FSMC_D2,,,EVENTOUT,
PortD,PD1,,,,,,,,,,CAN1_TX,,,FSMC_D3,,,EVENTOUT,
PortD,PD2,,,TIM3_ETR,,,,,,UART5_RX,,,,SDIO_CMD,DCMI_D11,,EVENTOUT,
PortD,PD3,,,,,,,,USART2_CTS,,,,,FSMC_CLK,,,EVENTOUT,
PortD,PD4,,,,,,,,USART2_RTS,,,,,FSMC_NOE,,,EVENTOUT,
PortD,PD5,,,,,,,,USART2_TX,,,,,FSMC_NWE,,,EVENTOUT,
PortD,PD6,,,,,,,,USART2_RX,,,,,FSMC_NWAIT,,,EVENTOUT,
PortD,PD7,,,,,,,,USART2_CK,,,,,FSMC_NE1/FSMC_NCE2,,,EVENTOUT,
PortD,PD8,,,,,,,,USART3_TX,,,,,FSMC_D13,,,EVENTOUT,
PortD,PD9,,,,,,,,USART3_RX,,,,,FSMC_D14,,,EVENTOUT,
PortD,PD10,,,,,,,,USART3_CK,,,,,FSMC_D15,,,EVENTOUT,
PortD,PD11,,,,,,,,USART3_CTS,,,,,FSMC_A16,,,EVENTOUT,
PortD,PD12,,,TIM4_CH1,,,,,USART3_RTS,,,,,FSMC_A17,,,EVENTOUT,
PortD,PD13,,,TIM4_CH2,,,,,,,,,,FSMC_A18,,,EVENTOUT,
PortD,PD14,,,TIM4_CH3,,,,,,,,,,FSMC_D0,,,EVENTOUT,
PortD,PD15,,,TIM4_CH4,,,,,,,,,,FSMC_D1,,,EVENTOUT,
PortE,PE0,,,TIM4_ETR,,,,,,,,,,FSMC_NBL0,DCMI_D2,,EVENTOUT,
PortE,PE1,,,,,,,,,,,,,FSMC_NBL1,DCMI_D3,,EVENTOUT,
PortE,PE2,TRACECLK,,,,,,,,,,,ETH_MII_TXD3,FSMC_A23,,,EVENTOUT,
PortE,PE3,TRACED0,,,,,,,,,,,,FSMC_A19,,,EVENTOUT,
PortE,PE4,TRACED1,,,,,,,,,,,,FSMC_A20,DCMI_D4,,EVENTOUT,
PortE,PE5,TRACED2,,,TIM9_CH1,,,,,,,,,FSMC_A21,DCMI_D6,,EVENTOUT,
PortE,PE6,TRACED3,,,TIM9_CH2,,,,,,,,,FSMC_A22,DCMI_D7,,EVENTOUT,
PortE,PE7,,TIM1_ETR,,,,,,,,,,,FSMC_D4,,,EVENTOUT,
PortE,PE8,,TIM1_CH1N,,,,,,,,,,,FSMC_D5,,,EVENTOUT,
PortE,PE9,,TIM1_CH1,,,,,,,,,,,FSMC_D6,,,EVENTOUT,
PortE,PE10,,TIM1_CH2N,,,,,,,,,,,FSMC_D7,,,EVENTOUT,
PortE,PE11,,TIM1_CH2,,,,,,,,,,,FSMC_D8,,,EVENTOUT,
PortE,PE12,,TIM1_CH3N,,,,,,,,,,,FSMC_D9,,,EVENTOUT,
PortE,PE13,,TIM1_CH3,,,,,,,,,,,FSMC_D10,,,EVENTOUT,
PortE,PE14,,TIM1_CH4,,,,,,,,,,,FSMC_D11,,,EVENTOUT,
PortE,PE15,,TIM1_BKIN,,,,,,,,,,,FSMC_D12,,,EVENTOUT,
PortF,PF0,,,,,I2C2_SDA,,,,,,,,FSMC_A0,,,EVENTOUT,
PortF,PF1,,,,,I2C2_SCL,,,,,,,,FSMC_A1,,,EVENTOUT,
PortF,PF2,,,,,I2C2_SMBA,,,,,,,,FSMC_A2,,,EVENTOUT,
PortF,PF3,,,,,,,,,,,,,FSMC_A3,,,EVENTOUT,ADC3_IN9
PortF,PF4,,,,,,,,,,,,,FSMC_A4,,,EVENTOUT,ADC3_IN14
PortF,PF5,,,,,,,,,,,,,FSMC_A5,,,EVENTOUT,ADC3_IN15
PortF,PF6,,,,TIM10_CH1,,,,,,,,,FSMC_NIORD,,,EVENTOUT,ADC3_IN4
PortF,PF7,,,,TIM11_CH1,,,,,,,,,FSMC_NREG,,,EVENTOUT,ADC3_IN5
PortF,PF8,,,,,,,,,,TIM13_CH1,,,FSMC_NIOWR,,,EVENTOUT,ADC3_IN6
PortF,PF9,,,,,,,,,,TIM14_CH1,,,FSMC_CD,,,EVENTOUT,ADC3_IN7
PortF,PF10,,,,,,,,,,,,,FSMC_INTR,,,EVENTOUT,ADC3_IN8
PortF,PF11,,,,,,,,,,,,,,DCMI_D12,,EVENTOUT,
PortF,PF12,,,,,,,,,,,,,FSMC_A6,,,EVENTOUT,
PortF,PF13,,,,,,,,,,,,,FSMC_A7,,,EVENTOUT,
PortF,PF14,,,,,,,,,,,,,FSMC_A8,,,EVENTOUT,
PortF,PF15,,,,,,,,,,,,,FSMC_A9,,,EVENTOUT,
PortG,PG0,,,,,,,,,,,,,FSMC_A10,,,EVENTOUT,
PortG,PG1,,,,,,,,,,,,,FSMC_A11,,,EVENTOUT,
PortG,PG2,,,,,,,,,,,,,FSMC_A12,,,EVENTOUT,
PortG,PG3,,,,,,,,,,,,,FSMC_A13,,,EVENTOUT,
PortG,PG4,,,,,,,,,,,,,FSMC_A14,,,EVENTOUT,
PortG,PG5,,,,,,,,,,,,,FSMC_A15,,,EVENTOUT,
PortG,PG6,,,,,,,,,,,,,FSMC_INT2,,,EVENTOUT,
PortG,PG7,,,,,,,,,USART6_CK,,,,FSMC_INT3,,,EVENTOUT,
PortG,PG8,,,,,,,,,USART6_RTS,,,ETH_PPS_OUT,,,,EVENTOUT,
PortG,PG9,,,,,,,,,USART6_RX,,,,FSMC_NE2/FSMC_NCE3,,,EVENTOUT,
PortG,PG10,,,,,,,,,,,,,FSMC_NCE4_1/FSMC_NE3,,,EVENTOUT,
PortG,PG11,,,,,,,,,,,,ETH_MII_TX_EN/ETH_RMII_TX_EN,FSMC_NCE4_2,,,EVENTOUT,
PortG,PG12,,,,,,,,,USART6_RTS,,,,FSMC_NE4,,,EVENTOUT,
PortG,PG13,,,,,,,,,USART6_CTS,,,ETH_MII_TXD0/ETH_RMII_TXD0,FSMC_A24,,,EVENTOUT,
PortG,PG14,,,,,,,,,USART6_TX,,,ETH_MII_TXD1/ETH_RMII_TXD1,FSMC_A25,,,EVENTOUT,
PortG,PG15,,,,,,,,,USART6_CTS,,,,,DCMI_D13,,EVENTOUT,
PortH,PH0,,,,,,,,,,,,,,,,EVENTOUT,
PortH,PH1,,,,,,,,,,,,,,,,EVENTOUT,
PortH,PH2,,,,,,,,,,,,ETH_MII_CRS,,,,EVENTOUT,
PortH,PH3,,,,,,,,,,,,ETH_MII_COL,,,,EVENTOUT,
PortH,PH4,,,,,I2C2_SCL,,,,,,OTG_HS_ULPI_NXT,,,,,EVENTOUT,
PortH,PH5,,,,,I2C2_SDA,,,,,,,,,,,EVENTOUT,
PortH,PH6,,,,,I2C2_SMBA,,,,,TIM12_CH1,,ETH_MII_RXD2,,,,EVENTOUT,
PortH,PH7,,,,,I2C3_SCL,,,,,,,ETH_MII_RXD3,,,,EVENTOUT,
PortH,PH8,,,,,I2C3_SDA,,,,,,,,,DCMI_HSYNC,,EVENTOUT,
PortH,PH9,,,,,I2C3_SMBA,,,,,TIM12_CH2,,,,DCMI_D0,,EVENTOUT,
PortH,PH10,,,TIM5_CH1,,,,,,,,,,,DCMI_D1,,EVENTOUT,
PortH,PH11,,,TIM5_CH2,,,,,,,,,,,DCMI_D2,,EVENTOUT,
PortH,PH12,,,TIM5_CH3,,,,,,,,,,,DCMI_D3,,EVENTOUT,
PortH,PH13,,,,TIM8_CH1N,,,,,,CAN1_TX,,,,,,EVENTOUT,
PortH,PH14,,,,TIM8_CH2N,,,,,,,,,,DCMI_D4,,EVENTOUT,
PortH,PH15,,,,TIM8_CH3N,,,,,,,,,,DCMI_D11,,EVENTOUT,
PortI,PI0,,,TIM5_CH4,,,SPI2_NSS/I2S2_WS,,,,,,,,DCMI_D13,,EVENTOUT,
PortI,PI1,,,,,,SPI2_SCK/I2S2_CK,,,,,,,,DCMI_D8,,EVENTOUT,
PortI,PI2,,,,TIM8_CH4,,SPI2_MISO,I2S2ext_SD,,,,,,,DCMI_D9,,EVENTOUT,
PortI,PI3,,,,TIM8_ETR,,SPI2_MOSI/I2S2_SD,,,,,,,,DCMI_D10,,EVENTOUT,
PortI,PI4,,,,TIM8_BKIN,,,,,,,,,,DCMI_D5,,EVENTOUT,
PortI,PI5,,,,TIM8_CH1,,,,,,,,,,DCMI_VSYNC,,EVENTOUT,
PortI,PI6,,,,TIM8_CH2,,,,,,,,,,DCMI_D6,,EVENTOUT,
PortI,PI7,,,,TIM8_CH3,,,,,,,,,,DCMI_D7,,EVENTOUT,
PortI,PI8,,,,,,,,,,,,,,,,EVENTOUT,
PortI,PI9,,,,,,,,,,CAN1_RX,,,,,,EVENTOUT,
PortI,PI10,,,,,,,,,,,,ETH_MII_RX_ER,,,,EVENTOUT,
PortI,PI11,,,,,,,,,,,OTG_HS_ULPI_DIR,,,,,EVENTOUT,
PA0,,TIM2_CH1/TIM2_ETR,TIM5_CH1,TIM8_ETR,,,,USART2_CTS,UART4_TX,,,ETH_MII_CRS,,,,EVENTOUT,ADC123_IN0
PA1,,TIM2_CH2,TIM5_CH2,,,,,USART2_RTS,UART4_RX,,,ETH_MII_RX_CLK/ETH_RMII_REF_CLK,,,,EVENTOUT,ADC123_IN1
PA2,,TIM2_CH3,TIM5_CH3,TIM9_CH1,,,,USART2_TX,,,,ETH_MDIO,,,,EVENTOUT,ADC123_IN2
PA3,,TIM2_CH4,TIM5_CH4,TIM9_CH2,,,,USART2_RX,,,OTG_HS_ULPI_D0,ETH_MII_COL,,,,EVENTOUT,ADC123_IN3
PA4,,,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_CK,,,,,OTG_HS_SOF,DCMI_HSYNC,,EVENTOUT,ADC12_IN4
PA5,,TIM2_CH1/TIM2_ETR,,TIM8_CH1N,,SPI1_SCK,,,,,OTG_HS_ULPI_CK,,,,,EVENTOUT,ADC12_IN5
PA6,,TIM1_BKIN,TIM3_CH1,TIM8_BKIN,,SPI1_MISO,,,,TIM13_CH1,,,,DCMI_PIXCK,,EVENTOUT,ADC12_IN6
PA7,,TIM1_CH1N,TIM3_CH2,TIM8_CH1N,,SPI1_MOSI,,,,TIM14_CH1,,ETH_MII_RX_DV/ETH_RMII_CRS_DV,,,,EVENTOUT,ADC12_IN7
PA8,MCO1,TIM1_CH1,,,I2C3_SCL,,,USART1_CK,,,OTG_FS_SOF,,,,,EVENTOUT,
PA9,,TIM1_CH2,,,I2C3_SMBA,,,USART1_TX,,,,,,DCMI_D0,,EVENTOUT,
PA10,,TIM1_CH3,,,,,,USART1_RX,,,OTG_FS_ID,,,DCMI_D1,,EVENTOUT,
PA11,,TIM1_CH4,,,,,,USART1_CTS,,CAN1_RX,OTG_FS_DM,,,,,EVENTOUT,
PA12,,TIM1_ETR,,,,,,USART1_RTS,,CAN1_TX,OTG_FS_DP,,,,,EVENTOUT,
PA13,JTMS/SWDIO,,,,,,,,,,,,,,,EVENTOUT,
PA14,JTCK/SWCLK,,,,,,,,,,,,,,,EVENTOUT,
PA15,JTDI,TIM2_CH1/TIM2_ETR,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,,,,,,,,,EVENTOUT,
PB0,,TIM1_CH2N,TIM3_CH3,TIM8_CH2N,,,,,,,OTG_HS_ULPI_D1,ETH_MII_RXD2,,,,EVENTOUT,ADC12_IN8
PB1,,TIM1_CH3N,TIM3_CH4,TIM8_CH3N,,,,,,,OTG_HS_ULPI_D2,ETH_MII_RXD3,,,,EVENTOUT,ADC12_IN9
PB2,,,,,,,,,,,,,,,,EVENTOUT,
PB3,JTDO/TRACESWO,TIM2_CH2,,,,SPI1_SCK,SPI3_SCK/I2S3_CK,,,,,,,,,EVENTOUT,
PB4,NJTRST,,TIM3_CH1,,,SPI1_MISO,SPI3_MISO,I2S3ext_SD,,,,,,,,EVENTOUT,
PB5,,,TIM3_CH2,,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI/I2S3_SD,,,CAN2_RX,OTG_HS_ULPI_D7,ETH_PPS_OUT,,DCMI_D10,,EVENTOUT,
PB6,,,TIM4_CH1,,I2C1_SCL,,,USART1_TX,,CAN2_TX,,,,DCMI_D5,,EVENTOUT,
PB7,,,TIM4_CH2,,I2C1_SDA,,,USART1_RX,,,,,FSMC_NL,DCMI_VSYNC,,EVENTOUT,
PB8,,,TIM4_CH3,TIM10_CH1,I2C1_SCL,,,,,CAN1_RX,,ETH_MII_TXD3,SDIO_D4,DCMI_D6,,EVENTOUT,
PB9,,,TIM4_CH4,TIM11_CH1,I2C1_SDA,SPI2_NSS/I2S2_WS,,,,CAN1_TX,,,SDIO_D5,DCMI_D7,,EVENTOUT,
PB10,,TIM2_CH3,,,I2C2_SCL,SPI2_SCK/I2S2_CK,,USART3_TX,,,OTG_HS_ULPI_D3,ETH_MII_RX_ER,,,,EVENTOUT,
PB11,,TIM2_CH4,,,I2C2_SDA,,,USART3_RX,,,OTG_HS_ULPI_D4,ETH_MII_TX_EN/ETH_RMII_TX_EN,,,,EVENTOUT,
PB12,,TIM1_BKIN,,,I2C2_SMBA,SPI2_NSS/I2S2_WS,,USART3_CK,,CAN2_RX,OTG_HS_ULPI_D5,ETH_MII_TXD0/ETH_RMII_TXD0,OTG_HS_ID,,,EVENTOUT,
PB13,,TIM1_CH1N,,,,SPI2_SCK/I2S2_CK,,USART3_CTS,,CAN2_TX,OTG_HS_ULPI_D6,ETH_MII_TXD1/ETH_RMII_TXD1,,,,EVENTOUT,
PB14,,TIM1_CH2N,,TIM8_CH2N,,SPI2_MISO,I2S2ext_SD,USART3_RTS,,TIM12_CH1,,,OTG_HS_DM,,,EVENTOUT,
PB15,RTC_REFIN,TIM1_CH3N,,TIM8_CH3N,,SPI2_MOSI/I2S2_SD,,,,TIM12_CH2,,,OTG_HS_DP,,,EVENTOUT,
PC0,,,,,,,,,,,OTG_HS_ULPI_STP,,,,,EVENTOUT,ADC123_IN10
PC1,,,,,,,,,,,,ETH_MDC,,,,EVENTOUT,ADC123_IN11
PC2,,,,,,SPI2_MISO,I2S2ext_SD,,,,OTG_HS_ULPI_DIR,ETH_MII_TXD2,,,,EVENTOUT,ADC123_IN12
PC3,,,,,,SPI2_MOSI/I2S2_SD,,,,,OTG_HS_ULPI_NXT,ETH_MII_TX_CLK,,,,EVENTOUT,ADC123_IN13
PC4,,,,,,,,,,,,ETH_MII_RXD0/ETH_RMII_RXD0,,,,EVENTOUT,ADC123_IN14
PC5,,,,,,,,,,,,ETH_MII_RXD1/ETH_RMII_RXD1,,,,EVENTOUT,ADC123_IN15
PC6,,,TIM3_CH1,TIM8_CH1,,I2S2_MCK,,,USART6_TX,,,,SDIO_D6,DCMI_D0,,EVENTOUT,
PC7,,,TIM3_CH2,TIM8_CH2,,,I2S3_MCK,,USART6_RX,,,,SDIO_D7,DCMI_D1,,EVENTOUT,
PC8,,,TIM3_CH3,TIM8_CH3,,,,,USART6_CK,,,,SDIO_D0,DCMI_D2,,EVENTOUT,
PC9,MCO2,,TIM3_CH4,TIM8_CH4,I2C3_SDA,I2S_CKIN,,,,,,,SDIO_D1,DCMI_D3,,EVENTOUT,
PC10,,,,,,,SPI3_SCK/I2S3_CK,USART3_TX,UART4_TX,,,,SDIO_D2,DCMI_D8,,EVENTOUT,
PC11,,,,,,I2S3ext_SD,SPI3_MISO,USART3_RX,UART4_RX,,,,SDIO_D3,DCMI_D4,,EVENTOUT,
PC12,,,,,,,SPI3_MOSI/I2S3_SD,USART3_CK,UART5_TX,,,,SDIO_CK,DCMI_D9,,EVENTOUT,
PC13,,,,,,,,,,,,,,,,EVENTOUT,
PC14,,,,,,,,,,,,,,,,EVENTOUT,
PC15,,,,,,,,,,,,,,,,EVENTOUT,
PD0,,,,,,,,,,CAN1_RX,,,FSMC_D2,,,EVENTOUT,
PD1,,,,,,,,,,CAN1_TX,,,FSMC_D3,,,EVENTOUT,
PD2,,,TIM3_ETR,,,,,,UART5_RX,,,,SDIO_CMD,DCMI_D11,,EVENTOUT,
PD3,,,,,,,,USART2_CTS,,,,,FSMC_CLK,,,EVENTOUT,
PD4,,,,,,,,USART2_RTS,,,,,FSMC_NOE,,,EVENTOUT,
PD5,,,,,,,,USART2_TX,,,,,FSMC_NWE,,,EVENTOUT,
PD6,,,,,,,,USART2_RX,,,,,FSMC_NWAIT,,,EVENTOUT,
PD7,,,,,,,,USART2_CK,,,,,FSMC_NE1/FSMC_NCE2,,,EVENTOUT,
PD8,,,,,,,,USART3_TX,,,,,FSMC_D13,,,EVENTOUT,
PD9,,,,,,,,USART3_RX,,,,,FSMC_D14,,,EVENTOUT,
PD10,,,,,,,,USART3_CK,,,,,FSMC_D15,,,EVENTOUT,
PD11,,,,,,,,USART3_CTS,,,,,FSMC_A16,,,EVENTOUT,
PD12,,,TIM4_CH1,,,,,USART3_RTS,,,,,FSMC_A17,,,EVENTOUT,
PD13,,,TIM4_CH2,,,,,,,,,,FSMC_A18,,,EVENTOUT,
PD14,,,TIM4_CH3,,,,,,,,,,FSMC_D0,,,EVENTOUT,
PD15,,,TIM4_CH4,,,,,,,,,,FSMC_D1,,,EVENTOUT,
PE0,,,TIM4_ETR,,,,,,,,,,FSMC_NBL0,DCMI_D2,,EVENTOUT,
PE1,,,,,,,,,,,,,FSMC_NBL1,DCMI_D3,,EVENTOUT,
PE2,TRACECLK,,,,,,,,,,,ETH_MII_TXD3,FSMC_A23,,,EVENTOUT,
PE3,TRACED0,,,,,,,,,,,,FSMC_A19,,,EVENTOUT,
PE4,TRACED1,,,,,,,,,,,,FSMC_A20,DCMI_D4,,EVENTOUT,
PE5,TRACED2,,,TIM9_CH1,,,,,,,,,FSMC_A21,DCMI_D6,,EVENTOUT,
PE6,TRACED3,,,TIM9_CH2,,,,,,,,,FSMC_A22,DCMI_D7,,EVENTOUT,
PE7,,TIM1_ETR,,,,,,,,,,,FSMC_D4,,,EVENTOUT,
PE8,,TIM1_CH1N,,,,,,,,,,,FSMC_D5,,,EVENTOUT,
PE9,,TIM1_CH1,,,,,,,,,,,FSMC_D6,,,EVENTOUT,
PE10,,TIM1_CH2N,,,,,,,,,,,FSMC_D7,,,EVENTOUT,
PE11,,TIM1_CH2,,,,,,,,,,,FSMC_D8,,,EVENTOUT,
PE12,,TIM1_CH3N,,,,,,,,,,,FSMC_D9,,,EVENTOUT,
PE13,,TIM1_CH3,,,,,,,,,,,FSMC_D10,,,EVENTOUT,
PE14,,TIM1_CH4,,,,,,,,,,,FSMC_D11,,,EVENTOUT,
PE15,,TIM1_BKIN,,,,,,,,,,,FSMC_D12,,,EVENTOUT,
PF0,,,,,I2C2_SDA,,,,,,,,FSMC_A0,,,EVENTOUT,
PF1,,,,,I2C2_SCL,,,,,,,,FSMC_A1,,,EVENTOUT,
PF2,,,,,I2C2_SMBA,,,,,,,,FSMC_A2,,,EVENTOUT,
PF3,,,,,,,,,,,,,FSMC_A3,,,EVENTOUT,ADC3_IN9
PF4,,,,,,,,,,,,,FSMC_A4,,,EVENTOUT,ADC3_IN14
PF5,,,,,,,,,,,,,FSMC_A5,,,EVENTOUT,ADC3_IN15
PF6,,,,TIM10_CH1,,,,,,,,,FSMC_NIORD,,,EVENTOUT,ADC3_IN4
PF7,,,,TIM11_CH1,,,,,,,,,FSMC_NREG,,,EVENTOUT,ADC3_IN5
PF8,,,,,,,,,,TIM13_CH1,,,FSMC_NIOWR,,,EVENTOUT,ADC3_IN6
PF9,,,,,,,,,,TIM14_CH1,,,FSMC_CD,,,EVENTOUT,ADC3_IN7
PF10,,,,,,,,,,,,,FSMC_INTR,,,EVENTOUT,ADC3_IN8
PF11,,,,,,,,,,,,,,DCMI_D12,,EVENTOUT,
PF12,,,,,,,,,,,,,FSMC_A6,,,EVENTOUT,
PF13,,,,,,,,,,,,,FSMC_A7,,,EVENTOUT,
PF14,,,,,,,,,,,,,FSMC_A8,,,EVENTOUT,
PF15,,,,,,,,,,,,,FSMC_A9,,,EVENTOUT,
PG0,,,,,,,,,,,,,FSMC_A10,,,EVENTOUT,
PG1,,,,,,,,,,,,,FSMC_A11,,,EVENTOUT,
PG2,,,,,,,,,,,,,FSMC_A12,,,EVENTOUT,
PG3,,,,,,,,,,,,,FSMC_A13,,,EVENTOUT,
PG4,,,,,,,,,,,,,FSMC_A14,,,EVENTOUT,
PG5,,,,,,,,,,,,,FSMC_A15,,,EVENTOUT,
PG6,,,,,,,,,,,,,FSMC_INT2,,,EVENTOUT,
PG7,,,,,,,,,USART6_CK,,,,FSMC_INT3,,,EVENTOUT,
PG8,,,,,,,,,USART6_RTS,,,ETH_PPS_OUT,,,,EVENTOUT,
PG9,,,,,,,,,USART6_RX,,,,FSMC_NE2/FSMC_NCE3,,,EVENTOUT,
PG10,,,,,,,,,,,,,FSMC_NCE4_1/FSMC_NE3,,,EVENTOUT,
PG11,,,,,,,,,,,,ETH_MII_TX_EN/ETH_RMII_TX_EN,FSMC_NCE4_2,,,EVENTOUT,
PG12,,,,,,,,,USART6_RTS,,,,FSMC_NE4,,,EVENTOUT,
PG13,,,,,,,,,USART6_CTS,,,ETH_MII_TXD0/ETH_RMII_TXD0,FSMC_A24,,,EVENTOUT,
PG14,,,,,,,,,USART6_TX,,,ETH_MII_TXD1/ETH_RMII_TXD1,FSMC_A25,,,EVENTOUT,
PG15,,,,,,,,,USART6_CTS,,,,,DCMI_D13,,EVENTOUT,
PH0,,,,,,,,,,,,,,,,EVENTOUT,
PH1,,,,,,,,,,,,,,,,EVENTOUT,
PH2,,,,,,,,,,,,ETH_MII_CRS,,,,EVENTOUT,
PH3,,,,,,,,,,,,ETH_MII_COL,,,,EVENTOUT,
PH4,,,,,I2C2_SCL,,,,,,OTG_HS_ULPI_NXT,,,,,EVENTOUT,
PH5,,,,,I2C2_SDA,,,,,,,,,,,EVENTOUT,
PH6,,,,,I2C2_SMBA,,,,,TIM12_CH1,,ETH_MII_RXD2,,,,EVENTOUT,
PH7,,,,,I2C3_SCL,,,,,,,ETH_MII_RXD3,,,,EVENTOUT,
PH8,,,,,I2C3_SDA,,,,,,,,,DCMI_HSYNC,,EVENTOUT,
PH9,,,,,I2C3_SMBA,,,,,TIM12_CH2,,,,DCMI_D0,,EVENTOUT,
PH10,,,TIM5_CH1,,,,,,,,,,,DCMI_D1,,EVENTOUT,
PH11,,,TIM5_CH2,,,,,,,,,,,DCMI_D2,,EVENTOUT,
PH12,,,TIM5_CH3,,,,,,,,,,,DCMI_D3,,EVENTOUT,
PH13,,,,TIM8_CH1N,,,,,,CAN1_TX,,,,,,EVENTOUT,
PH14,,,,TIM8_CH2N,,,,,,,,,,DCMI_D4,,EVENTOUT,
PH15,,,,TIM8_CH3N,,,,,,,,,,DCMI_D11,,EVENTOUT,
PI0,,,TIM5_CH4,,,SPI2_NSS/I2S2_WS,,,,,,,,DCMI_D13,,EVENTOUT,
PI1,,,,,,SPI2_SCK/I2S2_CK,,,,,,,,DCMI_D8,,EVENTOUT,
PI2,,,,TIM8_CH4,,SPI2_MISO,I2S2ext_SD,,,,,,,DCMI_D9,,EVENTOUT,
PI3,,,,TIM8_ETR,,SPI2_MOSI/I2S2_SD,,,,,,,,DCMI_D10,,EVENTOUT,
PI4,,,,TIM8_BKIN,,,,,,,,,,DCMI_D5,,EVENTOUT,
PI5,,,,TIM8_CH1,,,,,,,,,,DCMI_VSYNC,,EVENTOUT,
PI6,,,,TIM8_CH2,,,,,,,,,,DCMI_D6,,EVENTOUT,
PI7,,,,TIM8_CH3,,,,,,,,,,DCMI_D7,,EVENTOUT,
PI8,,,,,,,,,,,,,,,,EVENTOUT,
PI9,,,,,,,,,,CAN1_RX,,,,,,EVENTOUT,
PI10,,,,,,,,,,,,ETH_MII_RX_ER,,,,EVENTOUT,
PI11,,,,,,,,,,,OTG_HS_ULPI_DIR,,,,,EVENTOUT,

1 Port Port,,AF0,AF1,AF2,AF3,AF4,AF5,AF6,AF7,AF8,AF9,AF10,AF11,AF12,AF13,AF14,AF15, AF0 AF1 AF2 AF3 AF4 AF5 AF6 AF7 AF8 AF9 AF10 AF11 AF12 AF13 AF14 AF15
2 ,,SYS,TIM1/2,TIM3/4/5,TIM8/9/10/11,I2C1/2/3,SPI1/SPI2/I2S2/I2S2ext,SPI3/I2Sext/I2S3,USART1/2/3/I2S3ext,UART4/5/USART6,CAN1/CAN2/TIM12/13/14,OTG_FS/OTG_HS,ETH,FSMC/SDIO/OTG_FS,DCMI,,,ADC SYS TIM1/2 TIM3/4/5 TIM8/9/10/11 I2C1/2/3 SPI1/SPI2/I2S2/I2S2ext SPI3/I2Sext/I2S3 USART1/2/3/I2S3ext UART4/5/USART6 CAN1/CAN2/TIM12/13/14 OTG_FS/OTG_HS ETH FSMC/SDIO/OTG_FS DCMI ADC
3 PortA PA0,,TIM2_CH1/TIM2_ETR,TIM5_CH1,TIM8_ETR,,,,USART2_CTS,UART4_TX,,,ETH_MII_CRS,,,,EVENTOUT,ADC123_IN0 PA0 TIM2_CH1/TIM2_ETR TIM5_CH1 TIM8_ETR USART2_CTS UART4_TX ETH_MII_CRS EVENTOUT ADC123_IN0
4 PortA PA1,,TIM2_CH2,TIM5_CH2,,,,,USART2_RTS,UART4_RX,,,ETH_MII_RX_CLK/ETH_RMII_REF_CLK,,,,EVENTOUT,ADC123_IN1 PA1 TIM2_CH2 TIM5_CH2 USART2_RTS UART4_RX ETH_MII_RX_CLK/ETH_RMII_REF_CLK EVENTOUT ADC123_IN1
5 PortA PA2,,TIM2_CH3,TIM5_CH3,TIM9_CH1,,,,USART2_TX,,,,ETH_MDIO,,,,EVENTOUT,ADC123_IN2 PA2 TIM2_CH3 TIM5_CH3 TIM9_CH1 USART2_TX ETH_MDIO EVENTOUT ADC123_IN2
6 PortA PA3,,TIM2_CH4,TIM5_CH4,TIM9_CH2,,,,USART2_RX,,,OTG_HS_ULPI_D0,ETH_MII_COL,,,,EVENTOUT,ADC123_IN3 PA3 TIM2_CH4 TIM5_CH4 TIM9_CH2 USART2_RX OTG_HS_ULPI_D0 ETH_MII_COL EVENTOUT ADC123_IN3
7 PortA PA4,,,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,USART2_CK,,,,,OTG_HS_SOF,DCMI_HSYNC,,EVENTOUT,ADC12_IN4 PA4 SPI1_NSS SPI3_NSS/I2S3_WS USART2_CK OTG_HS_SOF DCMI_HSYNC EVENTOUT ADC12_IN4
8 PortA PA5,,TIM2_CH1/TIM2_ETR,,TIM8_CH1N,,SPI1_SCK,,,,,OTG_HS_ULPI_CK,,,,,EVENTOUT,ADC12_IN5 PA5 TIM2_CH1/TIM2_ETR TIM8_CH1N SPI1_SCK OTG_HS_ULPI_CK EVENTOUT ADC12_IN5
9 PortA PA6,,TIM1_BKIN,TIM3_CH1,TIM8_BKIN,,SPI1_MISO,,,,TIM13_CH1,,,,DCMI_PIXCK,,EVENTOUT,ADC12_IN6 PA6 TIM1_BKIN TIM3_CH1 TIM8_BKIN SPI1_MISO TIM13_CH1 DCMI_PIXCK EVENTOUT ADC12_IN6
10 PortA PA7,,TIM1_CH1N,TIM3_CH2,TIM8_CH1N,,SPI1_MOSI,,,,TIM14_CH1,,ETH_MII_RX_DV/ETH_RMII_CRS_DV,,,,EVENTOUT,ADC12_IN7 PA7 TIM1_CH1N TIM3_CH2 TIM8_CH1N SPI1_MOSI TIM14_CH1 ETH_MII_RX_DV/ETH_RMII_CRS_DV EVENTOUT ADC12_IN7
11 PortA PA8,MCO1,TIM1_CH1,,,I2C3_SCL,,,USART1_CK,,,OTG_FS_SOF,,,,,EVENTOUT, PA8 MCO1 TIM1_CH1 I2C3_SCL USART1_CK OTG_FS_SOF EVENTOUT
12 PortA PA9,,TIM1_CH2,,,I2C3_SMBA,,,USART1_TX,,,,,,DCMI_D0,,EVENTOUT, PA9 TIM1_CH2 I2C3_SMBA USART1_TX DCMI_D0 EVENTOUT
13 PortA PA10,,TIM1_CH3,,,,,,USART1_RX,,,OTG_FS_ID,,,DCMI_D1,,EVENTOUT, PA10 TIM1_CH3 USART1_RX OTG_FS_ID DCMI_D1 EVENTOUT
14 PortA PA11,,TIM1_CH4,,,,,,USART1_CTS,,CAN1_RX,OTG_FS_DM,,,,,EVENTOUT, PA11 TIM1_CH4 USART1_CTS CAN1_RX OTG_FS_DM EVENTOUT
15 PortA PA12,,TIM1_ETR,,,,,,USART1_RTS,,CAN1_TX,OTG_FS_DP,,,,,EVENTOUT, PA12 TIM1_ETR USART1_RTS CAN1_TX OTG_FS_DP EVENTOUT
16 PortA PA13,JTMS/SWDIO,,,,,,,,,,,,,,,EVENTOUT, PA13 JTMS/SWDIO EVENTOUT
17 PortA PA14,JTCK/SWCLK,,,,,,,,,,,,,,,EVENTOUT, PA14 JTCK/SWCLK EVENTOUT
18 PortA PA15,JTDI,TIM2_CH1/TIM2_ETR,,,,SPI1_NSS,SPI3_NSS/I2S3_WS,,,,,,,,,EVENTOUT, PA15 JTDI TIM2_CH1/TIM2_ETR SPI1_NSS SPI3_NSS/I2S3_WS EVENTOUT
19 PortB PB0,,TIM1_CH2N,TIM3_CH3,TIM8_CH2N,,,,,,,OTG_HS_ULPI_D1,ETH_MII_RXD2,,,,EVENTOUT,ADC12_IN8 PB0 TIM1_CH2N TIM3_CH3 TIM8_CH2N OTG_HS_ULPI_D1 ETH_MII_RXD2 EVENTOUT ADC12_IN8
20 PortB PB1,,TIM1_CH3N,TIM3_CH4,TIM8_CH3N,,,,,,,OTG_HS_ULPI_D2,ETH_MII_RXD3,,,,EVENTOUT,ADC12_IN9 PB1 TIM1_CH3N TIM3_CH4 TIM8_CH3N OTG_HS_ULPI_D2 ETH_MII_RXD3 EVENTOUT ADC12_IN9
21 PortB PB2,,,,,,,,,,,,,,,,EVENTOUT, PB2 EVENTOUT
22 PortB PB3,JTDO/TRACESWO,TIM2_CH2,,,,SPI1_SCK,SPI3_SCK/I2S3_CK,,,,,,,,,EVENTOUT, PB3 JTDO/TRACESWO TIM2_CH2 SPI1_SCK SPI3_SCK/I2S3_CK EVENTOUT
23 PortB PB4,NJTRST,,TIM3_CH1,,,SPI1_MISO,SPI3_MISO,I2S3ext_SD,,,,,,,,EVENTOUT, PB4 NJTRST TIM3_CH1 SPI1_MISO SPI3_MISO I2S3ext_SD EVENTOUT
24 PortB PB5,,,TIM3_CH2,,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI/I2S3_SD,,,CAN2_RX,OTG_HS_ULPI_D7,ETH_PPS_OUT,,DCMI_D10,,EVENTOUT, PB5 TIM3_CH2 I2C1_SMBA SPI1_MOSI SPI3_MOSI/I2S3_SD CAN2_RX OTG_HS_ULPI_D7 ETH_PPS_OUT DCMI_D10 EVENTOUT
25 PortB PB6,,,TIM4_CH1,,I2C1_SCL,,,USART1_TX,,CAN2_TX,,,,DCMI_D5,,EVENTOUT, PB6 TIM4_CH1 I2C1_SCL USART1_TX CAN2_TX DCMI_D5 EVENTOUT
26 PortB PB7,,,TIM4_CH2,,I2C1_SDA,,,USART1_RX,,,,,FSMC_NL,DCMI_VSYNC,,EVENTOUT, PB7 TIM4_CH2 I2C1_SDA USART1_RX FSMC_NL DCMI_VSYNC EVENTOUT
27 PortB PB8,,,TIM4_CH3,TIM10_CH1,I2C1_SCL,,,,,CAN1_RX,,ETH_MII_TXD3,SDIO_D4,DCMI_D6,,EVENTOUT, PB8 TIM4_CH3 TIM10_CH1 I2C1_SCL CAN1_RX ETH_MII_TXD3 SDIO_D4 DCMI_D6 EVENTOUT
28 PortB PB9,,,TIM4_CH4,TIM11_CH1,I2C1_SDA,SPI2_NSS/I2S2_WS,,,,CAN1_TX,,,SDIO_D5,DCMI_D7,,EVENTOUT, PB9 TIM4_CH4 TIM11_CH1 I2C1_SDA SPI2_NSS/I2S2_WS CAN1_TX SDIO_D5 DCMI_D7 EVENTOUT
29 PortB PB10,,TIM2_CH3,,,I2C2_SCL,SPI2_SCK/I2S2_CK,,USART3_TX,,,OTG_HS_ULPI_D3,ETH_MII_RX_ER,,,,EVENTOUT, PB10 TIM2_CH3 I2C2_SCL SPI2_SCK/I2S2_CK USART3_TX OTG_HS_ULPI_D3 ETH_MII_RX_ER EVENTOUT
30 PortB PB11,,TIM2_CH4,,,I2C2_SDA,,,USART3_RX,,,OTG_HS_ULPI_D4,ETH_MII_TX_EN/ETH_RMII_TX_EN,,,,EVENTOUT, PB11 TIM2_CH4 I2C2_SDA USART3_RX OTG_HS_ULPI_D4 ETH_MII_TX_EN/ETH_RMII_TX_EN EVENTOUT
31 PortB PB12,,TIM1_BKIN,,,I2C2_SMBA,SPI2_NSS/I2S2_WS,,USART3_CK,,CAN2_RX,OTG_HS_ULPI_D5,ETH_MII_TXD0/ETH_RMII_TXD0,OTG_HS_ID,,,EVENTOUT, PB12 TIM1_BKIN I2C2_SMBA SPI2_NSS/I2S2_WS USART3_CK CAN2_RX OTG_HS_ULPI_D5 ETH_MII_TXD0/ETH_RMII_TXD0 OTG_HS_ID EVENTOUT
32 PortB PB13,,TIM1_CH1N,,,,SPI2_SCK/I2S2_CK,,USART3_CTS,,CAN2_TX,OTG_HS_ULPI_D6,ETH_MII_TXD1/ETH_RMII_TXD1,,,,EVENTOUT, PB13 TIM1_CH1N SPI2_SCK/I2S2_CK USART3_CTS CAN2_TX OTG_HS_ULPI_D6 ETH_MII_TXD1/ETH_RMII_TXD1 EVENTOUT
33 PortB PB14,,TIM1_CH2N,,TIM8_CH2N,,SPI2_MISO,I2S2ext_SD,USART3_RTS,,TIM12_CH1,,,OTG_HS_DM,,,EVENTOUT, PB14 TIM1_CH2N TIM8_CH2N SPI2_MISO I2S2ext_SD USART3_RTS TIM12_CH1 OTG_HS_DM EVENTOUT
34 PortB PB15,RTC_REFIN,TIM1_CH3N,,TIM8_CH3N,,SPI2_MOSI/I2S2_SD,,,,TIM12_CH2,,,OTG_HS_DP,,,EVENTOUT, PB15 RTC_REFIN TIM1_CH3N TIM8_CH3N SPI2_MOSI/I2S2_SD TIM12_CH2 OTG_HS_DP EVENTOUT
35 PortC PC0,,,,,,,,,,,OTG_HS_ULPI_STP,,,,,EVENTOUT,ADC123_IN10 PC0 OTG_HS_ULPI_STP EVENTOUT ADC123_IN10
36 PortC PC1,,,,,,,,,,,,ETH_MDC,,,,EVENTOUT,ADC123_IN11 PC1 ETH_MDC EVENTOUT ADC123_IN11
37 PortC PC2,,,,,,SPI2_MISO,I2S2ext_SD,,,,OTG_HS_ULPI_DIR,ETH_MII_TXD2,,,,EVENTOUT,ADC123_IN12 PC2 SPI2_MISO I2S2ext_SD OTG_HS_ULPI_DIR ETH_MII_TXD2 EVENTOUT ADC123_IN12
38 PortC PC3,,,,,,SPI2_MOSI/I2S2_SD,,,,,OTG_HS_ULPI_NXT,ETH_MII_TX_CLK,,,,EVENTOUT,ADC123_IN13 PC3 SPI2_MOSI/I2S2_SD OTG_HS_ULPI_NXT ETH_MII_TX_CLK EVENTOUT ADC123_IN13
39 PortC PC4,,,,,,,,,,,,ETH_MII_RXD0/ETH_RMII_RXD0,,,,EVENTOUT,ADC123_IN14 PC4 ETH_MII_RXD0/ETH_RMII_RXD0 EVENTOUT ADC123_IN14
40 PortC PC5,,,,,,,,,,,,ETH_MII_RXD1/ETH_RMII_RXD1,,,,EVENTOUT,ADC123_IN15 PC5 ETH_MII_RXD1/ETH_RMII_RXD1 EVENTOUT ADC123_IN15
41 PortC PC6,,,TIM3_CH1,TIM8_CH1,,I2S2_MCK,,,USART6_TX,,,,SDIO_D6,DCMI_D0,,EVENTOUT, PC6 TIM3_CH1 TIM8_CH1 I2S2_MCK USART6_TX SDIO_D6 DCMI_D0 EVENTOUT
42 PortC PC7,,,TIM3_CH2,TIM8_CH2,,,I2S3_MCK,,USART6_RX,,,,SDIO_D7,DCMI_D1,,EVENTOUT, PC7 TIM3_CH2 TIM8_CH2 I2S3_MCK USART6_RX SDIO_D7 DCMI_D1 EVENTOUT
43 PortC PC8,,,TIM3_CH3,TIM8_CH3,,,,,USART6_CK,,,,SDIO_D0,DCMI_D2,,EVENTOUT, PC8 TIM3_CH3 TIM8_CH3 USART6_CK SDIO_D0 DCMI_D2 EVENTOUT
44 PortC PC9,MCO2,,TIM3_CH4,TIM8_CH4,I2C3_SDA,I2S_CKIN,,,,,,,SDIO_D1,DCMI_D3,,EVENTOUT, PC9 MCO2 TIM3_CH4 TIM8_CH4 I2C3_SDA I2S_CKIN SDIO_D1 DCMI_D3 EVENTOUT
45 PortC PC10,,,,,,,SPI3_SCK/I2S3_CK,USART3_TX,UART4_TX,,,,SDIO_D2,DCMI_D8,,EVENTOUT, PC10 SPI3_SCK/I2S3_CK USART3_TX UART4_TX SDIO_D2 DCMI_D8 EVENTOUT
46 PortC PC11,,,,,,I2S3ext_SD,SPI3_MISO,USART3_RX,UART4_RX,,,,SDIO_D3,DCMI_D4,,EVENTOUT, PC11 I2S3ext_SD SPI3_MISO USART3_RX UART4_RX SDIO_D3 DCMI_D4 EVENTOUT
47 PortC PC12,,,,,,,SPI3_MOSI/I2S3_SD,USART3_CK,UART5_TX,,,,SDIO_CK,DCMI_D9,,EVENTOUT, PC12 SPI3_MOSI/I2S3_SD USART3_CK UART5_TX SDIO_CK DCMI_D9 EVENTOUT
48 PortC PC13,,,,,,,,,,,,,,,,EVENTOUT, PC13 EVENTOUT
49 PortC PC14,,,,,,,,,,,,,,,,EVENTOUT, PC14 EVENTOUT
50 PortC PC15,,,,,,,,,,,,,,,,EVENTOUT, PC15 EVENTOUT
51 PortD PD0,,,,,,,,,,CAN1_RX,,,FSMC_D2,,,EVENTOUT, PD0 CAN1_RX FSMC_D2 EVENTOUT
52 PortD PD1,,,,,,,,,,CAN1_TX,,,FSMC_D3,,,EVENTOUT, PD1 CAN1_TX FSMC_D3 EVENTOUT
53 PortD PD2,,,TIM3_ETR,,,,,,UART5_RX,,,,SDIO_CMD,DCMI_D11,,EVENTOUT, PD2 TIM3_ETR UART5_RX SDIO_CMD DCMI_D11 EVENTOUT
54 PortD PD3,,,,,,,,USART2_CTS,,,,,FSMC_CLK,,,EVENTOUT, PD3 USART2_CTS FSMC_CLK EVENTOUT
55 PortD PD4,,,,,,,,USART2_RTS,,,,,FSMC_NOE,,,EVENTOUT, PD4 USART2_RTS FSMC_NOE EVENTOUT
56 PortD PD5,,,,,,,,USART2_TX,,,,,FSMC_NWE,,,EVENTOUT, PD5 USART2_TX FSMC_NWE EVENTOUT
57 PortD PD6,,,,,,,,USART2_RX,,,,,FSMC_NWAIT,,,EVENTOUT, PD6 USART2_RX FSMC_NWAIT EVENTOUT
58 PortD PD7,,,,,,,,USART2_CK,,,,,FSMC_NE1/FSMC_NCE2,,,EVENTOUT, PD7 USART2_CK FSMC_NE1/FSMC_NCE2 EVENTOUT
59 PortD PD8,,,,,,,,USART3_TX,,,,,FSMC_D13,,,EVENTOUT, PD8 USART3_TX FSMC_D13 EVENTOUT
60 PortD PD9,,,,,,,,USART3_RX,,,,,FSMC_D14,,,EVENTOUT, PD9 USART3_RX FSMC_D14 EVENTOUT
61 PortD PD10,,,,,,,,USART3_CK,,,,,FSMC_D15,,,EVENTOUT, PD10 USART3_CK FSMC_D15 EVENTOUT
62 PortD PD11,,,,,,,,USART3_CTS,,,,,FSMC_A16,,,EVENTOUT, PD11 USART3_CTS FSMC_A16 EVENTOUT
63 PortD PD12,,,TIM4_CH1,,,,,USART3_RTS,,,,,FSMC_A17,,,EVENTOUT, PD12 TIM4_CH1 USART3_RTS FSMC_A17 EVENTOUT
64 PortD PD13,,,TIM4_CH2,,,,,,,,,,FSMC_A18,,,EVENTOUT, PD13 TIM4_CH2 FSMC_A18 EVENTOUT
65 PortD PD14,,,TIM4_CH3,,,,,,,,,,FSMC_D0,,,EVENTOUT, PD14 TIM4_CH3 FSMC_D0 EVENTOUT
66 PortD PD15,,,TIM4_CH4,,,,,,,,,,FSMC_D1,,,EVENTOUT, PD15 TIM4_CH4 FSMC_D1 EVENTOUT
67 PortE PE0,,,TIM4_ETR,,,,,,,,,,FSMC_NBL0,DCMI_D2,,EVENTOUT, PE0 TIM4_ETR FSMC_NBL0 DCMI_D2 EVENTOUT
68 PortE PE1,,,,,,,,,,,,,FSMC_NBL1,DCMI_D3,,EVENTOUT, PE1 FSMC_NBL1 DCMI_D3 EVENTOUT
69 PortE PE2,TRACECLK,,,,,,,,,,,ETH_MII_TXD3,FSMC_A23,,,EVENTOUT, PE2 TRACECLK ETH_MII_TXD3 FSMC_A23 EVENTOUT
70 PortE PE3,TRACED0,,,,,,,,,,,,FSMC_A19,,,EVENTOUT, PE3 TRACED0 FSMC_A19 EVENTOUT
71 PortE PE4,TRACED1,,,,,,,,,,,,FSMC_A20,DCMI_D4,,EVENTOUT, PE4 TRACED1 FSMC_A20 DCMI_D4 EVENTOUT
72 PortE PE5,TRACED2,,,TIM9_CH1,,,,,,,,,FSMC_A21,DCMI_D6,,EVENTOUT, PE5 TRACED2 TIM9_CH1 FSMC_A21 DCMI_D6 EVENTOUT
73 PortE PE6,TRACED3,,,TIM9_CH2,,,,,,,,,FSMC_A22,DCMI_D7,,EVENTOUT, PE6 TRACED3 TIM9_CH2 FSMC_A22 DCMI_D7 EVENTOUT
74 PortE PE7,,TIM1_ETR,,,,,,,,,,,FSMC_D4,,,EVENTOUT, PE7 TIM1_ETR FSMC_D4 EVENTOUT
75 PortE PE8,,TIM1_CH1N,,,,,,,,,,,FSMC_D5,,,EVENTOUT, PE8 TIM1_CH1N FSMC_D5 EVENTOUT
76 PortE PE9,,TIM1_CH1,,,,,,,,,,,FSMC_D6,,,EVENTOUT, PE9 TIM1_CH1 FSMC_D6 EVENTOUT
77 PortE PE10,,TIM1_CH2N,,,,,,,,,,,FSMC_D7,,,EVENTOUT, PE10 TIM1_CH2N FSMC_D7 EVENTOUT
78 PortE PE11,,TIM1_CH2,,,,,,,,,,,FSMC_D8,,,EVENTOUT, PE11 TIM1_CH2 FSMC_D8 EVENTOUT
79 PortE PE12,,TIM1_CH3N,,,,,,,,,,,FSMC_D9,,,EVENTOUT, PE12 TIM1_CH3N FSMC_D9 EVENTOUT
80 PortE PE13,,TIM1_CH3,,,,,,,,,,,FSMC_D10,,,EVENTOUT, PE13 TIM1_CH3 FSMC_D10 EVENTOUT
81 PortE PE14,,TIM1_CH4,,,,,,,,,,,FSMC_D11,,,EVENTOUT, PE14 TIM1_CH4 FSMC_D11 EVENTOUT
82 PortE PE15,,TIM1_BKIN,,,,,,,,,,,FSMC_D12,,,EVENTOUT, PE15 TIM1_BKIN FSMC_D12 EVENTOUT
83 PortF PF0,,,,,I2C2_SDA,,,,,,,,FSMC_A0,,,EVENTOUT, PF0 I2C2_SDA FSMC_A0 EVENTOUT
84 PortF PF1,,,,,I2C2_SCL,,,,,,,,FSMC_A1,,,EVENTOUT, PF1 I2C2_SCL FSMC_A1 EVENTOUT
85 PortF PF2,,,,,I2C2_SMBA,,,,,,,,FSMC_A2,,,EVENTOUT, PF2 I2C2_SMBA FSMC_A2 EVENTOUT
86 PortF PF3,,,,,,,,,,,,,FSMC_A3,,,EVENTOUT,ADC3_IN9 PF3 FSMC_A3 EVENTOUT ADC3_IN9
87 PortF PF4,,,,,,,,,,,,,FSMC_A4,,,EVENTOUT,ADC3_IN14 PF4 FSMC_A4 EVENTOUT ADC3_IN14
88 PortF PF5,,,,,,,,,,,,,FSMC_A5,,,EVENTOUT,ADC3_IN15 PF5 FSMC_A5 EVENTOUT ADC3_IN15
89 PortF PF6,,,,TIM10_CH1,,,,,,,,,FSMC_NIORD,,,EVENTOUT,ADC3_IN4 PF6 TIM10_CH1 FSMC_NIORD EVENTOUT ADC3_IN4
90 PortF PF7,,,,TIM11_CH1,,,,,,,,,FSMC_NREG,,,EVENTOUT,ADC3_IN5 PF7 TIM11_CH1 FSMC_NREG EVENTOUT ADC3_IN5
91 PortF PF8,,,,,,,,,,TIM13_CH1,,,FSMC_NIOWR,,,EVENTOUT,ADC3_IN6 PF8 TIM13_CH1 FSMC_NIOWR EVENTOUT ADC3_IN6
92 PortF PF9,,,,,,,,,,TIM14_CH1,,,FSMC_CD,,,EVENTOUT,ADC3_IN7 PF9 TIM14_CH1 FSMC_CD EVENTOUT ADC3_IN7
93 PortF PF10,,,,,,,,,,,,,FSMC_INTR,,,EVENTOUT,ADC3_IN8 PF10 FSMC_INTR EVENTOUT ADC3_IN8
94 PortF PF11,,,,,,,,,,,,,,DCMI_D12,,EVENTOUT, PF11 DCMI_D12 EVENTOUT
95 PortF PF12,,,,,,,,,,,,,FSMC_A6,,,EVENTOUT, PF12 FSMC_A6 EVENTOUT
96 PortF PF13,,,,,,,,,,,,,FSMC_A7,,,EVENTOUT, PF13 FSMC_A7 EVENTOUT
97 PortF PF14,,,,,,,,,,,,,FSMC_A8,,,EVENTOUT, PF14 FSMC_A8 EVENTOUT
98 PortF PF15,,,,,,,,,,,,,FSMC_A9,,,EVENTOUT, PF15 FSMC_A9 EVENTOUT
99 PortG PG0,,,,,,,,,,,,,FSMC_A10,,,EVENTOUT, PG0 FSMC_A10 EVENTOUT
100 PortG PG1,,,,,,,,,,,,,FSMC_A11,,,EVENTOUT, PG1 FSMC_A11 EVENTOUT
101 PortG PG2,,,,,,,,,,,,,FSMC_A12,,,EVENTOUT, PG2 FSMC_A12 EVENTOUT
102 PortG PG3,,,,,,,,,,,,,FSMC_A13,,,EVENTOUT, PG3 FSMC_A13 EVENTOUT
103 PortG PG4,,,,,,,,,,,,,FSMC_A14,,,EVENTOUT, PG4 FSMC_A14 EVENTOUT
104 PortG PG5,,,,,,,,,,,,,FSMC_A15,,,EVENTOUT, PG5 FSMC_A15 EVENTOUT
105 PortG PG6,,,,,,,,,,,,,FSMC_INT2,,,EVENTOUT, PG6 FSMC_INT2 EVENTOUT
106 PortG PG7,,,,,,,,,USART6_CK,,,,FSMC_INT3,,,EVENTOUT, PG7 USART6_CK FSMC_INT3 EVENTOUT
107 PortG PG8,,,,,,,,,USART6_RTS,,,ETH_PPS_OUT,,,,EVENTOUT, PG8 USART6_RTS ETH_PPS_OUT EVENTOUT
108 PortG PG9,,,,,,,,,USART6_RX,,,,FSMC_NE2/FSMC_NCE3,,,EVENTOUT, PG9 USART6_RX FSMC_NE2/FSMC_NCE3 EVENTOUT
109 PortG PG10,,,,,,,,,,,,,FSMC_NCE4_1/FSMC_NE3,,,EVENTOUT, PG10 FSMC_NCE4_1/FSMC_NE3 EVENTOUT
110 PortG PG11,,,,,,,,,,,,ETH_MII_TX_EN/ETH_RMII_TX_EN,FSMC_NCE4_2,,,EVENTOUT, PG11 ETH_MII_TX_EN/ETH_RMII_TX_EN FSMC_NCE4_2 EVENTOUT
111 PortG PG12,,,,,,,,,USART6_RTS,,,,FSMC_NE4,,,EVENTOUT, PG12 USART6_RTS FSMC_NE4 EVENTOUT
112 PortG PG13,,,,,,,,,USART6_CTS,,,ETH_MII_TXD0/ETH_RMII_TXD0,FSMC_A24,,,EVENTOUT, PG13 USART6_CTS ETH_MII_TXD0/ETH_RMII_TXD0 FSMC_A24 EVENTOUT
113 PortG PG14,,,,,,,,,USART6_TX,,,ETH_MII_TXD1/ETH_RMII_TXD1,FSMC_A25,,,EVENTOUT, PG14 USART6_TX ETH_MII_TXD1/ETH_RMII_TXD1 FSMC_A25 EVENTOUT
114 PortG PG15,,,,,,,,,USART6_CTS,,,,,DCMI_D13,,EVENTOUT, PG15 USART6_CTS DCMI_D13 EVENTOUT
115 PortH PH0,,,,,,,,,,,,,,,,EVENTOUT, PH0 EVENTOUT
116 PortH PH1,,,,,,,,,,,,,,,,EVENTOUT, PH1 EVENTOUT
117 PortH PH2,,,,,,,,,,,,ETH_MII_CRS,,,,EVENTOUT, PH2 ETH_MII_CRS EVENTOUT
118 PortH PH3,,,,,,,,,,,,ETH_MII_COL,,,,EVENTOUT, PH3 ETH_MII_COL EVENTOUT
119 PortH PH4,,,,,I2C2_SCL,,,,,,OTG_HS_ULPI_NXT,,,,,EVENTOUT, PH4 I2C2_SCL OTG_HS_ULPI_NXT EVENTOUT
120 PortH PH5,,,,,I2C2_SDA,,,,,,,,,,,EVENTOUT, PH5 I2C2_SDA EVENTOUT
121 PortH PH6,,,,,I2C2_SMBA,,,,,TIM12_CH1,,ETH_MII_RXD2,,,,EVENTOUT, PH6 I2C2_SMBA TIM12_CH1 ETH_MII_RXD2 EVENTOUT
122 PortH PH7,,,,,I2C3_SCL,,,,,,,ETH_MII_RXD3,,,,EVENTOUT, PH7 I2C3_SCL ETH_MII_RXD3 EVENTOUT
123 PortH PH8,,,,,I2C3_SDA,,,,,,,,,DCMI_HSYNC,,EVENTOUT, PH8 I2C3_SDA DCMI_HSYNC EVENTOUT
124 PortH PH9,,,,,I2C3_SMBA,,,,,TIM12_CH2,,,,DCMI_D0,,EVENTOUT, PH9 I2C3_SMBA TIM12_CH2 DCMI_D0 EVENTOUT
125 PortH PH10,,,TIM5_CH1,,,,,,,,,,,DCMI_D1,,EVENTOUT, PH10 TIM5_CH1 DCMI_D1 EVENTOUT
126 PortH PH11,,,TIM5_CH2,,,,,,,,,,,DCMI_D2,,EVENTOUT, PH11 TIM5_CH2 DCMI_D2 EVENTOUT
127 PortH PH12,,,TIM5_CH3,,,,,,,,,,,DCMI_D3,,EVENTOUT, PH12 TIM5_CH3 DCMI_D3 EVENTOUT
128 PortH PH13,,,,TIM8_CH1N,,,,,,CAN1_TX,,,,,,EVENTOUT, PH13 TIM8_CH1N CAN1_TX EVENTOUT
129 PortH PH14,,,,TIM8_CH2N,,,,,,,,,,DCMI_D4,,EVENTOUT, PH14 TIM8_CH2N DCMI_D4 EVENTOUT
130 PortH PH15,,,,TIM8_CH3N,,,,,,,,,,DCMI_D11,,EVENTOUT, PH15 TIM8_CH3N DCMI_D11 EVENTOUT
131 PortI PI0,,,TIM5_CH4,,,SPI2_NSS/I2S2_WS,,,,,,,,DCMI_D13,,EVENTOUT, PI0 TIM5_CH4 SPI2_NSS/I2S2_WS DCMI_D13 EVENTOUT
132 PortI PI1,,,,,,SPI2_SCK/I2S2_CK,,,,,,,,DCMI_D8,,EVENTOUT, PI1 SPI2_SCK/I2S2_CK DCMI_D8 EVENTOUT
133 PortI PI2,,,,TIM8_CH4,,SPI2_MISO,I2S2ext_SD,,,,,,,DCMI_D9,,EVENTOUT, PI2 TIM8_CH4 SPI2_MISO I2S2ext_SD DCMI_D9 EVENTOUT
134 PortI PI3,,,,TIM8_ETR,,SPI2_MOSI/I2S2_SD,,,,,,,,DCMI_D10,,EVENTOUT, PI3 TIM8_ETR SPI2_MOSI/I2S2_SD DCMI_D10 EVENTOUT
135 PortI PI4,,,,TIM8_BKIN,,,,,,,,,,DCMI_D5,,EVENTOUT, PI4 TIM8_BKIN DCMI_D5 EVENTOUT
136 PortI PI5,,,,TIM8_CH1,,,,,,,,,,DCMI_VSYNC,,EVENTOUT, PI5 TIM8_CH1 DCMI_VSYNC EVENTOUT
137 PortI PI6,,,,TIM8_CH2,,,,,,,,,,DCMI_D6,,EVENTOUT, PI6 TIM8_CH2 DCMI_D6 EVENTOUT
138 PortI PI7,,,,TIM8_CH3,,,,,,,,,,DCMI_D7,,EVENTOUT, PI7 TIM8_CH3 DCMI_D7 EVENTOUT
139 PortI PI8,,,,,,,,,,,,,,,,EVENTOUT, PI8 EVENTOUT
140 PortI PI9,,,,,,,,,,CAN1_RX,,,,,,EVENTOUT, PI9 CAN1_RX EVENTOUT
141 PortI PI10,,,,,,,,,,,,ETH_MII_RX_ER,,,,EVENTOUT, PI10 ETH_MII_RX_ER EVENTOUT
142 PortI PI11,,,,,,,,,,,OTG_HS_ULPI_DIR,,,,,EVENTOUT, PI11 OTG_HS_ULPI_DIR EVENTOUT

View File

@ -0,0 +1,141 @@
Port,,AF0,AF1,AF2,AF3,AF4,AF5,AF6,AF7,AF8,AF9,AF10,AF11,AF12,AF13,AF14,AF15
PA0,-,TIM2_CH1,TIM5_CH1,TIM8_ETR,-,-,-,USART2_CTS_NSS,,UART4_TX,-,-,-,-,SAI1_EXTCLK,TIM2_ETR,EVENTOUT
PA1,-,TIM2_CH2,TIM5_CH2,-,I2C1_SMBA,SPI1_SCK,-,USART2_RTS_DE,,UART4_RX,-,OCTOSPIM_P1_DQS,-,-,-,TIM15_CH1N,EVENTOUT
PA2,-,TIM2_CH3,TIM5_CH3,-,-,-,-,USART2_TX,,LPUART1_TX,-,OCTOSPIM_P1_NCS,-,-,SAI2_EXTCLK,TIM15_CH1,EVENTOUT
PA3,-,TIM2_CH4,TIM5_CH4,SAI1_CK1,-,-,-,USART2_RX,,LPUART1_RX,-,OCTOSPIM_P1_CLK,-,-,SAI1_MCLK_A,TIM15_CH2,EVENTOUT
PA4,-,-,-,OCTOSPIM_P1_NCS,-,SPI1_NSS,SPI3_NSS,USART2_CK,,-,-,DCMI_HSYNC,-,-,SAI1_FS_B,LPTIM2_OUT,EVENTOUT
PA5,-,TIM2_CH1,TIM2_ETR,TIM8_CH1N,-,SPI1_SCK,-,-,,-,-,-,-,-,-,LPTIM2_ETR,EVENTOUT
PA6,-,TIM1_BKIN,TIM3_CH1,TIM8_BKIN,DCMI_PIXCLK,SPI1_MISO,-,USART3_CTS_NSS,,LPUART1_CTS,-,OCTOSPIM_P1_IO3,-,TIM1_BKIN,TIM8_BKIN,TIM16_CH1,EVENTOUT
PA7,-,TIM1_CH1N,TIM3_CH2,TIM8_CH1N,I2C3_SCL,SPI1_MOSI,-,-,,-,-,OCTOSPIM_P1_IO2,-,-,-,TIM17_CH1,EVENTOUT
PA8,MCO,TIM1_CH1,-,SAI1_CK2,-,-,-,USART1_CK,,-,-,OTG_FS_SOF,-,-,SAI1_SCK_A,LPTIM2_OUT,EVENTOUT
PA9,-,TIM1_CH2,-,SPI2_SCK,-,DCMI_D0,-,USART1_TX,,-,-,-,-,-,SAI1_FS_A,TIM15_BKIN,EVENTOUT
PA10,-,TIM1_CH3,-,SAI1_D1,-,DCMI_D1,-,USART1_RX,,-,-,OTG_FS_ID,-,-,SAI1_SD_A,TIM17_BKIN,EVENTOUT
PA11,-,TIM1_CH4,TIM1_BKIN2,-,-,SPI1_MISO,-,USART1_CTS_NSS,,-,CAN1_RX,OTG_FS_DM,-,TIM1_BKIN2,-,-,EVENTOUT
PA12,-,TIM1_ETR,-,-,-,SPI1_MOSI,-,USART1_RTS_DE,,-,CAN1_TX,OTG_FS_DP,-,-,-,-,EVENTOUT
PA13,JTMS/SWDIO,IR_OUT,-,-,-,-,-,-,,-,-,OTG_FS_NOE,-,-,SAI1_SD_B,-,EVENTOUT
PA14,JTCK/SWCLK,LPTIM1_OUT,-,-,I2C1_SMBA,I2C4_SMBA,-,-,,-,-,OTG_FS_SOF,-,-,SAI1_FS_B,-,EVENTOUT
PA15,JTDI,TIM2_CH1,TIM2_ETR,USART2_RX,-,SPI1_NSS,SPI3_NSS,USART3_RTS_DE,,UART4_RTS_DE,TSC_G3_IO1,-,-,-,SAI2_FS_B,-,EVENTOUT
PB0,-,TIM1_CH2N,TIM3_CH3,TIM8_CH2N,-,SPI1_NSS,-,USART3_CK,,-,-,OCTOSPIM_P1_IO1,-,COMP1_OUT,SAI1_EXTCLK,-,EVENTOUT
PB1,-,TIM1_CH3N,TIM3_CH4,TIM8_CH3N,-,-,DFSDM1_DATIN0,USART3_RTS_DE,,LPUART1_RTS_DE,-,OCTOSPIM_P1_IO0,-,-,-,LPTIM2_IN1,EVENTOUT
PB2,RTC_OUT,LPTIM1_OUT,-,-,I2C3_SMBA,-,DFSDM1_CKIN0,-,,-,-,OCTOSPIM_P1_DQS,LCD_B1,-,-,-,EVENTOUT
PB3,JTDO/TRACESWO,TIM2_CH2,-,-,-,SPI1_SCK,SPI3_SCK,USART1_RTS_DE,,-,-,OTG_FS_CRS_SYNC,-,-,SAI1_SCK_B,-,EVENTOUT
PB4,NJTRST,-,TIM3_CH1,-,I2C3_SDA,SPI1_MISO,SPI3_MISO,USART1_CTS_NSS,,UART5_RTS_DE,TSC_G2_IO1,DCMI_D12,-,-,SAI1_MCLK_B,TIM17_BKIN,EVENTOUT
PB5,-,LPTIM1_IN1,TIM3_CH2,-,I2C1_SMBA,SPI1_MOSI,SPI3_MOSI,USART1_CK,,UART5_CTS,TSC_G2_IO2,DCMI_D10,-,COMP2_OUT,SAI1_SD_B,TIM16_BKIN,EVENTOUT
PB6,-,LPTIM1_ETR,TIM4_CH1,TIM8_BKIN2,I2C1_SCL,I2C4_SCL,DFSDM1_DATIN5,USART1_TX,,-,TSC_G2_IO3,DCMI_D5,-,TIM8_BKIN2,SAI1_FS_B,TIM16_CH1N,EVENTOUT
PB7,-,LPTIM1_IN2,TIM4_CH2,TIM8_BKIN,I2C1_SDA,I2C4_SDA,DFSDM1_CKIN5,USART1_RX,,UART4_CTS,TSC_G2_IO4,DCMI_VSYNC,DSI_TE,FMC_NL,TIM8_BKIN,TIM17_CH1N,EVENTOUT
PB8,-,-,TIM4_CH3,SAI1_CK1,I2C1_SCL,DFSDM1_CKOUT,DFSDM1_DATIN6,-,,SDMMC1_CKIN,CAN1_RX,DCMI_D6,LCD_B1,SDMMC1_D4,SAI1_MCLK_A,TIM16_CH1,EVENTOUT
PB9,-,IR_OUT,TIM4_CH4,SAI1_D2,I2C1_SDA,SPI2_NSS,DFSDM1_CKIN6,-,,SDMMC1_CDIR,CAN1_TX,DCMI_D7,-,SDMMC1_D5,SAI1_FS_A,TIM17_CH1,EVENTOUT
PB10,-,TIM2_CH3,-,I2C4_SCL,I2C2_SCL,SPI2_SCK,DFSDM1_DATIN7,USART3_TX,,LPUART1_RX,TSC_SYNC,OCTOSPIM_P1_CLK,-,COMP1_OUT,SAI1_SCK_A,-,EVENTOUT
PB11,-,TIM2_CH4,-,I2C4_SDA,I2C2_SDA,-,DFSDM1_CKIN7,USART3_RX,,LPUART1_TX,-,OCTOSPIM_P1_NCS,DSI_TE,COMP2_OUT,-,-,EVENTOUT
PB12,-,TIM1_BKIN,-,TIM1_BKIN,I2C2_SMBA,SPI2_NSS,DFSDM1_DATIN1,USART3_CK,,LPUART1_RTS_DE,TSC_G1_IO1,-,-,-,SAI2_FS_A,TIM15_BKIN,EVENTOUT
PB13,-,TIM1_CH1N,-,-,I2C2_SCL,SPI2_SCK,DFSDM1_CKIN1,USART3_CTS_NSS,,LPUART1_CTS,TSC_G1_IO2,-,-,-,SAI2_SCK_A,TIM15_CH1N,EVENTOUT
PB14,-,TIM1_CH2N,-,TIM8_CH2N,I2C2_SDA,SPI2_MISO,DFSDM1_DATIN2,USART3_RTS_DE,,-,TSC_G1_IO3,-,-,-,SAI2_MCLK_A,TIM15_CH1,EVENTOUT
PB15,RTC_REFIN,TIM1_CH3N,-,TIM8_CH3N,-,SPI2_MOSI,DFSDM1_CKIN2,-,,-,TSC_G1_IO4,-,-,-,SAI2_SD_A,TIM15_CH2,EVENTOUT
PC0,-,LPTIM1_IN1,-,-,I2C3_SCL,-,DFSDM1_DATIN4,-,,LPUART1_RX,-,-,-,-,SAI2_FS_A,LPTIM2_IN1,EVENTOUT
PC1,TRACED0,LPTIM1_OUT,-,SPI2_MOSI,I2C3_SDA,-,DFSDM1_CKIN4,-,,LPUART1_TX,-,OCTOSPIM_P1_IO4,-,-,SAI1_SD_A,-,EVENTOUT
PC2,-,LPTIM1_IN2,-,-,-,SPI2_MISO,DFSDM1_CKOUT,-,,-,-,OCTOSPIM_P1_IO5,-,-,-,-,EVENTOUT
PC3,-,LPTIM1_ETR,-,SAI1_D1,-,SPI2_MOSI,-,-,,-,-,OCTOSPIM_P1_IO6,-,-,SAI1_SD_A,LPTIM2_ETR,EVENTOUT
PC4,-,-,-,-,-,-,-,USART3_TX,,-,-,OCTOSPIM_P1_IO7,-,-,-,-,EVENTOUT
PC5,-,-,-,SAI1_D3,-,-,-,USART3_RX,,-,-,-,-,-,-,-,EVENTOUT
PC6,-,-,TIM3_CH1,TIM8_CH1,-,-,DFSDM1_CKIN3,-,,SDMMC1_D0DIR,TSC_G4_IO1,DCMI_D0,LCD_R0,SDMMC1_D6,SAI2_MCLK_A,-,EVENTOUT
PC7,-,-,TIM3_CH2,TIM8_CH2,-,-,DFSDM1_DATIN3,-,,SDMMC1_D123DIR,TSC_G4_IO2,DCMI_D1,LCD_R1,SDMMC1_D7,SAI2_MCLK_B,-,EVENTOUT
PC8,-,-,TIM3_CH3,TIM8_CH3,-,-,-,-,,-,TSC_G4_IO3,DCMI_D2,-,SDMMC1_D0,-,-,EVENTOUT
PC9,TRACED0,TIM8_BKIN2,TIM3_CH4,TIM8_CH4,DCMI_D3,-,I2C3_SDA,-,,-,TSC_G4_IO4,OTG_FS_NOE,-,SDMMC1_D1,SAI2_EXTCLK,TIM8_BKIN2,EVENTOUT
PC10,TRACED1,-,-,-,-,-,SPI3_SCK,USART3_TX,,UART4_TX,TSC_G3_IO2,DCMI_D8,-,SDMMC1_D2,SAI2_SCK_B,-,EVENTOUT
PC11,-,-,-,-,DCMI_D2,OCTOSPIM_P1_NCS,SPI3_MISO,USART3_RX,,UART4_RX,TSC_G3_IO3,DCMI_D4,-,SDMMC1_D3,SAI2_MCLK_B,-,EVENTOUT
PC12,TRACED3,-,-,-,-,-,SPI3_MOSI,USART3_CK,,UART5_TX,TSC_G3_IO4,DCMI_D9,-,SDMMC1_CK,SAI2_SD_B,-,EVENTOUT
PC13,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PC14,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PC15,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PD0,-,-,-,-,-,SPI2_NSS,DFSDM1_DATIN7,-,,-,CAN1_RX,-,LCD_B4,FMC_D2,-,-,EVENTOUT
PD1,-,-,-,-,-,SPI2_SCK,DFSDM1_CKIN7,-,,-,CAN1_TX,-,LCD_B5,FMC_D3,-,-,EVENTOUT
PD2,TRACED2,-,TIM3_ETR,-,-,-,-,USART3_RTS_DE,,UART5_RX,TSC_SYNC,DCMI_D11,-,SDMMC1_CMD,-,-,EVENTOUT
PD3,-,-,-,SPI2_SCK,DCMI_D5,SPI2_MISO,DFSDM1_DATIN0,USART2_CTS_NSS,,-,-,OCTOSPIM_P2_NCS,LCD_CLK,FMC_CLK,-,-,EVENTOUT
PD4,-,-,-,-,-,SPI2_MOSI,DFSDM1_CKIN0,USART2_RTS_DE,,-,-,OCTOSPIM_P1_IO4,-,FMC_NOE,-,-,EVENTOUT
PD5,-,-,-,-,-,-,-,USART2_TX,,-,-,OCTOSPIM_P1_IO5,-,FMC_NWE,-,-,EVENTOUT
PD6,-,-,-,SAI1_D1,DCMI_D10,SPI3_MOSI,DFSDM1_DATIN1,USART2_RX,,-,-,OCTOSPIM_P1_IO6,LCD_DE,FMC_NWAIT,SAI1_SD_A,-,EVENTOUT
PD7,-,-,-,-,-,-,DFSDM1_CKIN1,USART2_CK,,-,-,OCTOSPIM_P1_IO7,-,FMC_NCE/FMC_NE1,-,-,EVENTOUT
PD8,-,-,-,-,-,-,-,USART3_TX,,-,-,DCMI_HSYNC,LCD_R3,FMC_D13,-,-,EVENTOUT
PD9,-,-,-,-,-,-,-,USART3_RX,,-,-,DCMI_PIXCLK,LCD_R4,FMC_D14,SAI2_MCLK_A,-,EVENTOUT
PD10,-,-,-,-,-,-,-,USART3_CK,,-,TSC_G6_IO1,-,LCD_R5,FMC_D15,SAI2_SCK_A,-,EVENTOUT
PD11,-,-,-,-,I2C4_SMBA,-,-,USART3_CTS_NSS,,-,TSC_G6_IO2,-,LCD_R6,FMC_A16,SAI2_SD_A,LPTIM2_ETR,EVENTOUT
PD12,-,-,TIM4_CH1,-,I2C4_SCL,-,-,USART3_RTS_DE,,-,TSC_G6_IO3,-,LCD_R7,FMC_A17,SAI2_FS_A,LPTIM2_IN1,EVENTOUT
PD13,-,-,TIM4_CH2,-,I2C4_SDA,-,-,-,,-,TSC_G6_IO4,-,-,FMC_A18,-,LPTIM2_OUT,EVENTOUT
PD14,-,-,TIM4_CH3,-,-,-,-,-,,-,-,-,LCD_B2,FMC_D0,-,-,EVENTOUT
PD15,-,-,TIM4_CH4,-,-,-,-,-,,-,-,-,LCD_B3,FMC_D1,-,-,EVENTOUT
PE0,-,-,TIM4_ETR,-,-,-,-,-,,-,-,DCMI_D2,LCD_HSYNC,FMC_NBL0,-,TIM16_CH1,EVENTOUT
PE1,-,-,-,-,-,-,-,-,,-,-,DCMI_D3,LCD_VSYNC,FMC_NBL1,-,TIM17_CH1,EVENTOUT
PE2,TRACECK,-,TIM3_ETR,SAI1_CK1,-,-,-,-,,-,TSC_G7_IO1,-,LCD_R0,FMC_A23,SAI1_MCLK_A,-,EVENTOUT
PE3,TRACED0,-,TIM3_CH1,OCTOSPIM_P1_DQS,-,-,-,-,,-,TSC_G7_IO2,-,LCD_R1,FMC_A19,SAI1_SD_B,-,EVENTOUT
PE4,TRACED1,-,TIM3_CH2,SAI1_D2,-,-,DFSDM1_DATIN3,-,,-,TSC_G7_IO3,DCMI_D4,LCD_B0,FMC_A20,SAI1_FS_A,-,EVENTOUT
PE5,TRACED2,-,TIM3_CH3,SAI1_CK2,-,-,DFSDM1_CKIN3,-,,-,TSC_G7_IO4,DCMI_D6,LCD_G0,FMC_A21,SAI1_SCK_A,-,EVENTOUT
PE6,TRACED3,-,TIM3_CH4,SAI1_D1,-,-,-,-,,-,-,DCMI_D7,LCD_G1,FMC_A22,SAI1_SD_A,-,EVENTOUT
PE7,-,TIM1_ETR,-,-,-,-,DFSDM1_DATIN2,-,,-,-,-,LCD_B6,FMC_D4,SAI1_SD_B,-,EVENTOUT
PE8,-,TIM1_CH1N,-,-,-,-,DFSDM1_CKIN2,-,,-,-,-,LCD_B7,FMC_D5,SAI1_SCK_B,-,EVENTOUT
PE9,-,TIM1_CH1,-,-,-,-,DFSDM1_CKOUT,-,,-,-,-,LCD_G2,FMC_D6,SAI1_FS_B,-,EVENTOUT
PE10,-,TIM1_CH2N,-,-,-,-,DFSDM1_DATIN4,-,,-,TSC_G5_IO1,OCTOSPIM_P1_CLK,LCD_G3,FMC_D7,SAI1_MCLK_B,-,EVENTOUT
PE11,-,TIM1_CH2,-,-,-,-,DFSDM1_CKIN4,-,,-,TSC_G5_IO2,OCTOSPIM_P1_NCS,LCD_G4,FMC_D8,-,-,EVENTOUT
PE12,-,TIM1_CH3N,-,-,-,SPI1_NSS,DFSDM1_DATIN5,-,,-,TSC_G5_IO3,OCTOSPIM_1_IO0,LCD_G5,FMC_D9,-,-,EVENTOUT
PE13,-,TIM1_CH3,-,-,-,SPI1_SCK,DFSDM1_CKIN5,-,,-,TSC_G5_IO4,OCTOSPIM_P1_IO1,LCD_G6,FMC_D10,-,-,EVENTOUT
PE14,-,TIM1_CH4,TIM1_BKIN2,TIM1_BKIN2,-,SPI1_MISO,-,-,,-,-,OCTOSPIM_P1_IO2,LCD_G7,FMC_D11,-,-,EVENTOUT
PE15,-,TIM1_BKIN,-,TIM1_BKIN,-,SPI1_MOSI,-,-,,-,-,OCTOSPIM_P1_IO3,LCD_R2,FMC_D12,-,-,EVENTOUT
PF0,-,-,-,-,I2C2_SDA,OCTOSPIM_P2_IO0,-,-,,-,-,-,-,FMC_A0,-,-,EVENTOUT
PF1,-,-,-,-,I2C2_SCL,OCTOSPIM_P2_IO1,-,-,,-,-,-,-,FMC_A1,-,-,EVENTOUT
PF2,-,-,-,-,I2C2_SMBA,OCTOSPIM_P2_IO2,-,-,,-,-,-,-,FMC_A2,-,-,EVENTOUT
PF3,-,-,-,-,-,OCTOSPIM_P2_IO3,-,-,,-,-,-,-,FMC_A3,-,-,EVENTOUT
PF4,-,-,-,-,-,OCTOSPIM_P2_CLK,-,-,,-,-,-,-,FMC_A4,-,-,EVENTOUT
PF5,-,-,-,-,-,-,-,-,,-,-,-,-,FMC_A5,-,-,EVENTOUT
PF6,-,TIM5_ETR,TIM5_CH1,-,-,-,-,-,,-,-,OCTOSPIM_P1_IO3,-,-,SAI1_SD_B,-,EVENTOUT
PF7,-,-,TIM5_CH2,-,-,-,-,-,,-,-,OCTOSPIM_P1_IO2,-,-,SAI1_MCLK_B,-,EVENTOUT
PF8,-,-,TIM5_CH3,-,-,-,-,-,,-,-,OCTOSPIM_P1_IO0,-,-,SAI1_SCK_B,-,EVENTOUT
PF9,-,-,TIM5_CH4,-,-,-,-,-,,-,-,OCTOSPIM_P1_IO1,-,-,SAI1_FS_B,TIM15_CH1,EVENTOUT
PF10,-,-,-,OCTOSPIM_P1_CLK,-,-,DFSDM1_CKOUT,-,,-,-,DCMI_D11,-,-,SAI1_D3,TIM15_CH2,EVENTOUT
PF11,-,-,-,-,-,-,-,-,,-,LCD_DE,DCMI_D12,DSI_TE,-,-,-,EVENTOUT
PF12,-,-,-,-,-,OCTOSPIM_P2_DQS,-,-,,-,-,-,LCD_B0,FMC_A6,-,-,EVENTOUT
PF13,-,-,-,-,I2C4_SMBA,-,DFSDM1_DATIN6,-,,-,-,-,LCD_B1,FMC_A7,-,-,EVENTOUT
PF14,-,-,-,-,I2C4_SCL,-,DFSDM1_CKIN6,-,,-,TSC_G8_IO1,-,LCD_G0,FMC_A8,-,-,EVENTOUT
PF15,-,-,-,-,I2C4_SDA,-,-,-,,-,TSC_G8_IO2,-,LCD_G1,FMC_A9,-,-,EVENTOUT
PG0,-,-,-,-,-,OCTOSPIM_P2_IO4,-,-,,-,TSC_G8_IO3,-,-,FMC_A10,-,-,EVENTOUT
PG1,-,-,-,-,-,OCTOSPIM_P2_IO5,-,-,,-,TSC_G8_IO4,-,-,FMC_A11,-,-,EVENTOUT
PG2,-,-,-,-,-,SPI1_SCK,-,-,,-,-,-,-,FMC_A12,SAI2_SCK_B,-,EVENTOUT
PG3,-,-,-,-,-,SPI1_MISO,-,-,,-,-,-,-,FMC_A13,SAI2_FS_B,-,EVENTOUT
PG4,-,-,-,-,-,SPI1_MOSI,-,-,,-,-,-,-,FMC_A14,SAI2_MCLK_B,-,EVENTOUT
PG5,-,-,-,-,-,SPI1_NSS,-,-,,LPUART1_CTS,-,-,-,FMC_A15,SAI2_SD_B,-,EVENTOUT
PG6,-,-,-,OCTOSPIM_P1_DQS,I2C3_SMBA,-,-,-,,LPUART1_RTS_DE,LCD_R1,-,DSI_TE,-,-,-,EVENTOUT
PG7,-,-,-,SAI1_CK1,I2C3_SCL,OCTOSPIM_P2_DQS,DFSDM1_CKOUT,-,,LPUART1_TX,-,-,-,FMC_INT,SAI1_MCLK_A,-,EVENTOUT
PG8,-,-,-,-,I2C3_SDA,-,-,-,,LPUART1_RX,-,-,-,-,-,-,EVENTOUT
PG9,-,-,-,-,-,OCTOSPIM_P2_IO6,SPI3_SCK,USART1_TX,,-,-,-,-,FMC_NCE/FMC_NE2,SAI2_SCK_A,TIM15_CH1N,EVENTOUT
PG10,-,LPTIM1_IN1,-,-,-,OCTOSPIM_P2_IO7,SPI3_MISO,USART1_RX,,-,-,-,-,FMC_NE3,SAI2_FS_A,TIM15_CH1,EVENTOUT
PG11,-,LPTIM1_IN2,-,OCTOSPIM_P1_IO5,-,-,SPI3_MOSI,USART1_CTS_NSS,,-,-,-,-,-,SAI2_MCLK_A,TIM15_CH2,EVENTOUT
PG12,-,LPTIM1_ETR,-,-,-,OCTOSPIM_P2_NCS,SPI3_NSS,USART1_RTS_DE,,-,-,-,-,FMC_NE4,SAI2_SD_A,-,EVENTOUT
PG13,-,-,-,-,I2C1_SDA,-,-,USART1_CK,,-,-,-,LCD_R0,FMC_A24,-,-,EVENTOUT
PG14,-,-,-,-,I2C1_SCL,-,-,-,,-,-,-,LCD_R1,FMC_A25,-,-,EVENTOUT
PG15,-,LPTIM1_OUT,-,-,I2C1_SMBA,OCTOSPIM_P2_DQS,-,-,,-,-,DCMI_D13,-,-,-,-,EVENTOUT
PH0,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PH1,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PH2,-,-,-,OCTOSPIM_P1_IO4,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PH3,-,-,-,-,-,-,-,-,,-,-,-,-,-,-,-,EVENTOUT
PH4,-,-,-,-,I2C2_SCL,OCTOSPIM_P2_DQS,-,-,,-,-,-,-,-,-,-,EVENTOUT
PH5,-,-,-,-,I2C2_SDA,-,-,-,,-,-,DCMI_PIXCLK,-,-,-,-,EVENTOUT
PH6,-,-,-,-,I2C2_SMBA,OCTOSPIM_P2_CLK,-,-,,-,-,DCMI_D8,-,-,-,-,EVENTOUT
PH7,-,-,-,-,I2C3_SCL,-,-,-,,-,-,DCMI_D9,-,-,-,-,EVENTOUT
PH8,-,-,-,-,I2C3_SDA,OCTOSPIM_P2_IO3,-,-,,-,-,DCMI_HSYNC,-,-,-,-,EVENTOUT
PH9,-,-,-,-,I2C3_SMBA,OCTOSPIM_P2_IO4,-,-,,-,-,DCMI_D0,-,-,-,-,EVENTOUT
PH10,-,-,TIM5_CH1,-,-,OCTOSPIM_P2_IO5,-,-,,-,-,DCMI_D1,-,-,-,-,EVENTOUT
PH11,-,-,TIM5_CH2,-,-,OCTOSPIM_P2_IO6,-,-,,-,-,DCMI_D2,-,-,-,-,EVENTOUT
PH12,-,-,TIM5_CH3,-,-,OCTOSPIM_P2_IO7,-,-,,-,-,DCMI_D3,-,-,-,-,EVENTOUT
PH13,-,-,-,TIM8_CH1N,-,-,-,-,,-,CAN1_TX,-,-,-,-,-,EVENTOUT
PH14,-,-,-,TIM8_CH2N,-,-,-,-,,-,-,DCMI_D4,-,-,-,-,EVENTOUT
PH15,-,-,-,TIM8_CH3N,-,OCTOSPIM_P2_IO6,-,-,,-,-,DCMI_D11,-,-,-,-,EVENTOUT
PI0,-,-,TIM5_CH4,OCTOSPIM_P1_IO5,-,SPI2_NSS,-,-,,-,-,DCMI_D13,-,-,-,-,EVENTOUT
PI1,-,-,-,-,-,SPI2_SCK,-,-,,-,-,DCMI_D8,-,-,-,-,EVENTOUT
PI2,-,-,-,TIM8_CH4,-,SPI2_MISO,-,-,,-,-,DCMI_D9,-,-,-,-,EVENTOUT
PI3,-,-,-,TIM8_ETR,-,SPI2_MOSI,-,-,,-,-,DCMI_D10,-,-,-,-,EVENTOUT
PI4,-,-,-,TIM8_BKIN,-,-,-,-,,-,-,DCMI_D5,-,-,-,-,EVENTOUT
PI5,-,-,-,TIM8_CH1,-,OCTOSPIM_P2_NCS,-,-,,-,-,DCMI_VSYNC,-,-,-,-,EVENTOUT
PI6,-,-,-,TIM8_CH2,-,OCTOSPIM_P2_CLK,-,-,,-,-,DCMI_D6,-,-,-,-,EVENTOUT
PI7,-,-,-,TIM8_CH3,-,-,-,-,,-,-,DCMI_D7,-,-,-,-,EVENTOUT
PI8,-,-,-,-,-,OCTOSPIM_P2_NCS,-,-,,-,-,DCMI_D12,-,-,-,-,EVENTOUT
PI9,-,-,-,-,-,OCTOSPIM_P2_IO2,-,-,,-,CAN1_RX,-,-,-,-,-,EVENTOUT
PI10,-,-,-,-,-,OCTOSPIM_P2_IO1,-,-,,-,-,-,-,-,-,-,EVENTOUT
PI11,-,-,-,-,-,OCTOSPIM_P2_IO0,-,-,,-,-,-,-,-,-,-,EVENTOUT
1 Port AF0 AF1 AF2 AF3 AF4 AF5 AF6 AF7 AF8 AF9 AF10 AF11 AF12 AF13 AF14 AF15
2 PA0 - TIM2_CH1 TIM5_CH1 TIM8_ETR - - - USART2_CTS_NSS UART4_TX - - - - SAI1_EXTCLK TIM2_ETR EVENTOUT
3 PA1 - TIM2_CH2 TIM5_CH2 - I2C1_SMBA SPI1_SCK - USART2_RTS_DE UART4_RX - OCTOSPIM_P1_DQS - - - TIM15_CH1N EVENTOUT
4 PA2 - TIM2_CH3 TIM5_CH3 - - - - USART2_TX LPUART1_TX - OCTOSPIM_P1_NCS - - SAI2_EXTCLK TIM15_CH1 EVENTOUT
5 PA3 - TIM2_CH4 TIM5_CH4 SAI1_CK1 - - - USART2_RX LPUART1_RX - OCTOSPIM_P1_CLK - - SAI1_MCLK_A TIM15_CH2 EVENTOUT
6 PA4 - - - OCTOSPIM_P1_NCS - SPI1_NSS SPI3_NSS USART2_CK - - DCMI_HSYNC - - SAI1_FS_B LPTIM2_OUT EVENTOUT
7 PA5 - TIM2_CH1 TIM2_ETR TIM8_CH1N - SPI1_SCK - - - - - - - - LPTIM2_ETR EVENTOUT
8 PA6 - TIM1_BKIN TIM3_CH1 TIM8_BKIN DCMI_PIXCLK SPI1_MISO - USART3_CTS_NSS LPUART1_CTS - OCTOSPIM_P1_IO3 - TIM1_BKIN TIM8_BKIN TIM16_CH1 EVENTOUT
9 PA7 - TIM1_CH1N TIM3_CH2 TIM8_CH1N I2C3_SCL SPI1_MOSI - - - - OCTOSPIM_P1_IO2 - - - TIM17_CH1 EVENTOUT
10 PA8 MCO TIM1_CH1 - SAI1_CK2 - - - USART1_CK - - OTG_FS_SOF - - SAI1_SCK_A LPTIM2_OUT EVENTOUT
11 PA9 - TIM1_CH2 - SPI2_SCK - DCMI_D0 - USART1_TX - - - - - SAI1_FS_A TIM15_BKIN EVENTOUT
12 PA10 - TIM1_CH3 - SAI1_D1 - DCMI_D1 - USART1_RX - - OTG_FS_ID - - SAI1_SD_A TIM17_BKIN EVENTOUT
13 PA11 - TIM1_CH4 TIM1_BKIN2 - - SPI1_MISO - USART1_CTS_NSS - CAN1_RX OTG_FS_DM - TIM1_BKIN2 - - EVENTOUT
14 PA12 - TIM1_ETR - - - SPI1_MOSI - USART1_RTS_DE - CAN1_TX OTG_FS_DP - - - - EVENTOUT
15 PA13 JTMS/SWDIO IR_OUT - - - - - - - - OTG_FS_NOE - - SAI1_SD_B - EVENTOUT
16 PA14 JTCK/SWCLK LPTIM1_OUT - - I2C1_SMBA I2C4_SMBA - - - - OTG_FS_SOF - - SAI1_FS_B - EVENTOUT
17 PA15 JTDI TIM2_CH1 TIM2_ETR USART2_RX - SPI1_NSS SPI3_NSS USART3_RTS_DE UART4_RTS_DE TSC_G3_IO1 - - - SAI2_FS_B - EVENTOUT
18 PB0 - TIM1_CH2N TIM3_CH3 TIM8_CH2N - SPI1_NSS - USART3_CK - - OCTOSPIM_P1_IO1 - COMP1_OUT SAI1_EXTCLK - EVENTOUT
19 PB1 - TIM1_CH3N TIM3_CH4 TIM8_CH3N - - DFSDM1_DATIN0 USART3_RTS_DE LPUART1_RTS_DE - OCTOSPIM_P1_IO0 - - - LPTIM2_IN1 EVENTOUT
20 PB2 RTC_OUT LPTIM1_OUT - - I2C3_SMBA - DFSDM1_CKIN0 - - - OCTOSPIM_P1_DQS LCD_B1 - - - EVENTOUT
21 PB3 JTDO/TRACESWO TIM2_CH2 - - - SPI1_SCK SPI3_SCK USART1_RTS_DE - - OTG_FS_CRS_SYNC - - SAI1_SCK_B - EVENTOUT
22 PB4 NJTRST - TIM3_CH1 - I2C3_SDA SPI1_MISO SPI3_MISO USART1_CTS_NSS UART5_RTS_DE TSC_G2_IO1 DCMI_D12 - - SAI1_MCLK_B TIM17_BKIN EVENTOUT
23 PB5 - LPTIM1_IN1 TIM3_CH2 - I2C1_SMBA SPI1_MOSI SPI3_MOSI USART1_CK UART5_CTS TSC_G2_IO2 DCMI_D10 - COMP2_OUT SAI1_SD_B TIM16_BKIN EVENTOUT
24 PB6 - LPTIM1_ETR TIM4_CH1 TIM8_BKIN2 I2C1_SCL I2C4_SCL DFSDM1_DATIN5 USART1_TX - TSC_G2_IO3 DCMI_D5 - TIM8_BKIN2 SAI1_FS_B TIM16_CH1N EVENTOUT
25 PB7 - LPTIM1_IN2 TIM4_CH2 TIM8_BKIN I2C1_SDA I2C4_SDA DFSDM1_CKIN5 USART1_RX UART4_CTS TSC_G2_IO4 DCMI_VSYNC DSI_TE FMC_NL TIM8_BKIN TIM17_CH1N EVENTOUT
26 PB8 - - TIM4_CH3 SAI1_CK1 I2C1_SCL DFSDM1_CKOUT DFSDM1_DATIN6 - SDMMC1_CKIN CAN1_RX DCMI_D6 LCD_B1 SDMMC1_D4 SAI1_MCLK_A TIM16_CH1 EVENTOUT
27 PB9 - IR_OUT TIM4_CH4 SAI1_D2 I2C1_SDA SPI2_NSS DFSDM1_CKIN6 - SDMMC1_CDIR CAN1_TX DCMI_D7 - SDMMC1_D5 SAI1_FS_A TIM17_CH1 EVENTOUT
28 PB10 - TIM2_CH3 - I2C4_SCL I2C2_SCL SPI2_SCK DFSDM1_DATIN7 USART3_TX LPUART1_RX TSC_SYNC OCTOSPIM_P1_CLK - COMP1_OUT SAI1_SCK_A - EVENTOUT
29 PB11 - TIM2_CH4 - I2C4_SDA I2C2_SDA - DFSDM1_CKIN7 USART3_RX LPUART1_TX - OCTOSPIM_P1_NCS DSI_TE COMP2_OUT - - EVENTOUT
30 PB12 - TIM1_BKIN - TIM1_BKIN I2C2_SMBA SPI2_NSS DFSDM1_DATIN1 USART3_CK LPUART1_RTS_DE TSC_G1_IO1 - - - SAI2_FS_A TIM15_BKIN EVENTOUT
31 PB13 - TIM1_CH1N - - I2C2_SCL SPI2_SCK DFSDM1_CKIN1 USART3_CTS_NSS LPUART1_CTS TSC_G1_IO2 - - - SAI2_SCK_A TIM15_CH1N EVENTOUT
32 PB14 - TIM1_CH2N - TIM8_CH2N I2C2_SDA SPI2_MISO DFSDM1_DATIN2 USART3_RTS_DE - TSC_G1_IO3 - - - SAI2_MCLK_A TIM15_CH1 EVENTOUT
33 PB15 RTC_REFIN TIM1_CH3N - TIM8_CH3N - SPI2_MOSI DFSDM1_CKIN2 - - TSC_G1_IO4 - - - SAI2_SD_A TIM15_CH2 EVENTOUT
34 PC0 - LPTIM1_IN1 - - I2C3_SCL - DFSDM1_DATIN4 - LPUART1_RX - - - - SAI2_FS_A LPTIM2_IN1 EVENTOUT
35 PC1 TRACED0 LPTIM1_OUT - SPI2_MOSI I2C3_SDA - DFSDM1_CKIN4 - LPUART1_TX - OCTOSPIM_P1_IO4 - - SAI1_SD_A - EVENTOUT
36 PC2 - LPTIM1_IN2 - - - SPI2_MISO DFSDM1_CKOUT - - - OCTOSPIM_P1_IO5 - - - - EVENTOUT
37 PC3 - LPTIM1_ETR - SAI1_D1 - SPI2_MOSI - - - - OCTOSPIM_P1_IO6 - - SAI1_SD_A LPTIM2_ETR EVENTOUT
38 PC4 - - - - - - - USART3_TX - - OCTOSPIM_P1_IO7 - - - - EVENTOUT
39 PC5 - - - SAI1_D3 - - - USART3_RX - - - - - - - EVENTOUT
40 PC6 - - TIM3_CH1 TIM8_CH1 - - DFSDM1_CKIN3 - SDMMC1_D0DIR TSC_G4_IO1 DCMI_D0 LCD_R0 SDMMC1_D6 SAI2_MCLK_A - EVENTOUT
41 PC7 - - TIM3_CH2 TIM8_CH2 - - DFSDM1_DATIN3 - SDMMC1_D123DIR TSC_G4_IO2 DCMI_D1 LCD_R1 SDMMC1_D7 SAI2_MCLK_B - EVENTOUT
42 PC8 - - TIM3_CH3 TIM8_CH3 - - - - - TSC_G4_IO3 DCMI_D2 - SDMMC1_D0 - - EVENTOUT
43 PC9 TRACED0 TIM8_BKIN2 TIM3_CH4 TIM8_CH4 DCMI_D3 - I2C3_SDA - - TSC_G4_IO4 OTG_FS_NOE - SDMMC1_D1 SAI2_EXTCLK TIM8_BKIN2 EVENTOUT
44 PC10 TRACED1 - - - - - SPI3_SCK USART3_TX UART4_TX TSC_G3_IO2 DCMI_D8 - SDMMC1_D2 SAI2_SCK_B - EVENTOUT
45 PC11 - - - - DCMI_D2 OCTOSPIM_P1_NCS SPI3_MISO USART3_RX UART4_RX TSC_G3_IO3 DCMI_D4 - SDMMC1_D3 SAI2_MCLK_B - EVENTOUT
46 PC12 TRACED3 - - - - - SPI3_MOSI USART3_CK UART5_TX TSC_G3_IO4 DCMI_D9 - SDMMC1_CK SAI2_SD_B - EVENTOUT
47 PC13 - - - - - - - - - - - - - - - EVENTOUT
48 PC14 - - - - - - - - - - - - - - - EVENTOUT
49 PC15 - - - - - - - - - - - - - - - EVENTOUT
50 PD0 - - - - - SPI2_NSS DFSDM1_DATIN7 - - CAN1_RX - LCD_B4 FMC_D2 - - EVENTOUT
51 PD1 - - - - - SPI2_SCK DFSDM1_CKIN7 - - CAN1_TX - LCD_B5 FMC_D3 - - EVENTOUT
52 PD2 TRACED2 - TIM3_ETR - - - - USART3_RTS_DE UART5_RX TSC_SYNC DCMI_D11 - SDMMC1_CMD - - EVENTOUT
53 PD3 - - - SPI2_SCK DCMI_D5 SPI2_MISO DFSDM1_DATIN0 USART2_CTS_NSS - - OCTOSPIM_P2_NCS LCD_CLK FMC_CLK - - EVENTOUT
54 PD4 - - - - - SPI2_MOSI DFSDM1_CKIN0 USART2_RTS_DE - - OCTOSPIM_P1_IO4 - FMC_NOE - - EVENTOUT
55 PD5 - - - - - - - USART2_TX - - OCTOSPIM_P1_IO5 - FMC_NWE - - EVENTOUT
56 PD6 - - - SAI1_D1 DCMI_D10 SPI3_MOSI DFSDM1_DATIN1 USART2_RX - - OCTOSPIM_P1_IO6 LCD_DE FMC_NWAIT SAI1_SD_A - EVENTOUT
57 PD7 - - - - - - DFSDM1_CKIN1 USART2_CK - - OCTOSPIM_P1_IO7 - FMC_NCE/FMC_NE1 - - EVENTOUT
58 PD8 - - - - - - - USART3_TX - - DCMI_HSYNC LCD_R3 FMC_D13 - - EVENTOUT
59 PD9 - - - - - - - USART3_RX - - DCMI_PIXCLK LCD_R4 FMC_D14 SAI2_MCLK_A - EVENTOUT
60 PD10 - - - - - - - USART3_CK - TSC_G6_IO1 - LCD_R5 FMC_D15 SAI2_SCK_A - EVENTOUT
61 PD11 - - - - I2C4_SMBA - - USART3_CTS_NSS - TSC_G6_IO2 - LCD_R6 FMC_A16 SAI2_SD_A LPTIM2_ETR EVENTOUT
62 PD12 - - TIM4_CH1 - I2C4_SCL - - USART3_RTS_DE - TSC_G6_IO3 - LCD_R7 FMC_A17 SAI2_FS_A LPTIM2_IN1 EVENTOUT
63 PD13 - - TIM4_CH2 - I2C4_SDA - - - - TSC_G6_IO4 - - FMC_A18 - LPTIM2_OUT EVENTOUT
64 PD14 - - TIM4_CH3 - - - - - - - - LCD_B2 FMC_D0 - - EVENTOUT
65 PD15 - - TIM4_CH4 - - - - - - - - LCD_B3 FMC_D1 - - EVENTOUT
66 PE0 - - TIM4_ETR - - - - - - - DCMI_D2 LCD_HSYNC FMC_NBL0 - TIM16_CH1 EVENTOUT
67 PE1 - - - - - - - - - - DCMI_D3 LCD_VSYNC FMC_NBL1 - TIM17_CH1 EVENTOUT
68 PE2 TRACECK - TIM3_ETR SAI1_CK1 - - - - - TSC_G7_IO1 - LCD_R0 FMC_A23 SAI1_MCLK_A - EVENTOUT
69 PE3 TRACED0 - TIM3_CH1 OCTOSPIM_P1_DQS - - - - - TSC_G7_IO2 - LCD_R1 FMC_A19 SAI1_SD_B - EVENTOUT
70 PE4 TRACED1 - TIM3_CH2 SAI1_D2 - - DFSDM1_DATIN3 - - TSC_G7_IO3 DCMI_D4 LCD_B0 FMC_A20 SAI1_FS_A - EVENTOUT
71 PE5 TRACED2 - TIM3_CH3 SAI1_CK2 - - DFSDM1_CKIN3 - - TSC_G7_IO4 DCMI_D6 LCD_G0 FMC_A21 SAI1_SCK_A - EVENTOUT
72 PE6 TRACED3 - TIM3_CH4 SAI1_D1 - - - - - - DCMI_D7 LCD_G1 FMC_A22 SAI1_SD_A - EVENTOUT
73 PE7 - TIM1_ETR - - - - DFSDM1_DATIN2 - - - - LCD_B6 FMC_D4 SAI1_SD_B - EVENTOUT
74 PE8 - TIM1_CH1N - - - - DFSDM1_CKIN2 - - - - LCD_B7 FMC_D5 SAI1_SCK_B - EVENTOUT
75 PE9 - TIM1_CH1 - - - - DFSDM1_CKOUT - - - - LCD_G2 FMC_D6 SAI1_FS_B - EVENTOUT
76 PE10 - TIM1_CH2N - - - - DFSDM1_DATIN4 - - TSC_G5_IO1 OCTOSPIM_P1_CLK LCD_G3 FMC_D7 SAI1_MCLK_B - EVENTOUT
77 PE11 - TIM1_CH2 - - - - DFSDM1_CKIN4 - - TSC_G5_IO2 OCTOSPIM_P1_NCS LCD_G4 FMC_D8 - - EVENTOUT
78 PE12 - TIM1_CH3N - - - SPI1_NSS DFSDM1_DATIN5 - - TSC_G5_IO3 OCTOSPIM_1_IO0 LCD_G5 FMC_D9 - - EVENTOUT
79 PE13 - TIM1_CH3 - - - SPI1_SCK DFSDM1_CKIN5 - - TSC_G5_IO4 OCTOSPIM_P1_IO1 LCD_G6 FMC_D10 - - EVENTOUT
80 PE14 - TIM1_CH4 TIM1_BKIN2 TIM1_BKIN2 - SPI1_MISO - - - - OCTOSPIM_P1_IO2 LCD_G7 FMC_D11 - - EVENTOUT
81 PE15 - TIM1_BKIN - TIM1_BKIN - SPI1_MOSI - - - - OCTOSPIM_P1_IO3 LCD_R2 FMC_D12 - - EVENTOUT
82 PF0 - - - - I2C2_SDA OCTOSPIM_P2_IO0 - - - - - - FMC_A0 - - EVENTOUT
83 PF1 - - - - I2C2_SCL OCTOSPIM_P2_IO1 - - - - - - FMC_A1 - - EVENTOUT
84 PF2 - - - - I2C2_SMBA OCTOSPIM_P2_IO2 - - - - - - FMC_A2 - - EVENTOUT
85 PF3 - - - - - OCTOSPIM_P2_IO3 - - - - - - FMC_A3 - - EVENTOUT
86 PF4 - - - - - OCTOSPIM_P2_CLK - - - - - - FMC_A4 - - EVENTOUT
87 PF5 - - - - - - - - - - - - FMC_A5 - - EVENTOUT
88 PF6 - TIM5_ETR TIM5_CH1 - - - - - - - OCTOSPIM_P1_IO3 - - SAI1_SD_B - EVENTOUT
89 PF7 - - TIM5_CH2 - - - - - - - OCTOSPIM_P1_IO2 - - SAI1_MCLK_B - EVENTOUT
90 PF8 - - TIM5_CH3 - - - - - - - OCTOSPIM_P1_IO0 - - SAI1_SCK_B - EVENTOUT
91 PF9 - - TIM5_CH4 - - - - - - - OCTOSPIM_P1_IO1 - - SAI1_FS_B TIM15_CH1 EVENTOUT
92 PF10 - - - OCTOSPIM_P1_CLK - - DFSDM1_CKOUT - - - DCMI_D11 - - SAI1_D3 TIM15_CH2 EVENTOUT
93 PF11 - - - - - - - - - LCD_DE DCMI_D12 DSI_TE - - - EVENTOUT
94 PF12 - - - - - OCTOSPIM_P2_DQS - - - - - LCD_B0 FMC_A6 - - EVENTOUT
95 PF13 - - - - I2C4_SMBA - DFSDM1_DATIN6 - - - - LCD_B1 FMC_A7 - - EVENTOUT
96 PF14 - - - - I2C4_SCL - DFSDM1_CKIN6 - - TSC_G8_IO1 - LCD_G0 FMC_A8 - - EVENTOUT
97 PF15 - - - - I2C4_SDA - - - - TSC_G8_IO2 - LCD_G1 FMC_A9 - - EVENTOUT
98 PG0 - - - - - OCTOSPIM_P2_IO4 - - - TSC_G8_IO3 - - FMC_A10 - - EVENTOUT
99 PG1 - - - - - OCTOSPIM_P2_IO5 - - - TSC_G8_IO4 - - FMC_A11 - - EVENTOUT
100 PG2 - - - - - SPI1_SCK - - - - - - FMC_A12 SAI2_SCK_B - EVENTOUT
101 PG3 - - - - - SPI1_MISO - - - - - - FMC_A13 SAI2_FS_B - EVENTOUT
102 PG4 - - - - - SPI1_MOSI - - - - - - FMC_A14 SAI2_MCLK_B - EVENTOUT
103 PG5 - - - - - SPI1_NSS - - LPUART1_CTS - - - FMC_A15 SAI2_SD_B - EVENTOUT
104 PG6 - - - OCTOSPIM_P1_DQS I2C3_SMBA - - - LPUART1_RTS_DE LCD_R1 - DSI_TE - - - EVENTOUT
105 PG7 - - - SAI1_CK1 I2C3_SCL OCTOSPIM_P2_DQS DFSDM1_CKOUT - LPUART1_TX - - - FMC_INT SAI1_MCLK_A - EVENTOUT
106 PG8 - - - - I2C3_SDA - - - LPUART1_RX - - - - - - EVENTOUT
107 PG9 - - - - - OCTOSPIM_P2_IO6 SPI3_SCK USART1_TX - - - - FMC_NCE/FMC_NE2 SAI2_SCK_A TIM15_CH1N EVENTOUT
108 PG10 - LPTIM1_IN1 - - - OCTOSPIM_P2_IO7 SPI3_MISO USART1_RX - - - - FMC_NE3 SAI2_FS_A TIM15_CH1 EVENTOUT
109 PG11 - LPTIM1_IN2 - OCTOSPIM_P1_IO5 - - SPI3_MOSI USART1_CTS_NSS - - - - - SAI2_MCLK_A TIM15_CH2 EVENTOUT
110 PG12 - LPTIM1_ETR - - - OCTOSPIM_P2_NCS SPI3_NSS USART1_RTS_DE - - - - FMC_NE4 SAI2_SD_A - EVENTOUT
111 PG13 - - - - I2C1_SDA - - USART1_CK - - - LCD_R0 FMC_A24 - - EVENTOUT
112 PG14 - - - - I2C1_SCL - - - - - - LCD_R1 FMC_A25 - - EVENTOUT
113 PG15 - LPTIM1_OUT - - I2C1_SMBA OCTOSPIM_P2_DQS - - - - DCMI_D13 - - - - EVENTOUT
114 PH0 - - - - - - - - - - - - - - - EVENTOUT
115 PH1 - - - - - - - - - - - - - - - EVENTOUT
116 PH2 - - - OCTOSPIM_P1_IO4 - - - - - - - - - - - EVENTOUT
117 PH3 - - - - - - - - - - - - - - - EVENTOUT
118 PH4 - - - - I2C2_SCL OCTOSPIM_P2_DQS - - - - - - - - - EVENTOUT
119 PH5 - - - - I2C2_SDA - - - - - DCMI_PIXCLK - - - - EVENTOUT
120 PH6 - - - - I2C2_SMBA OCTOSPIM_P2_CLK - - - - DCMI_D8 - - - - EVENTOUT
121 PH7 - - - - I2C3_SCL - - - - - DCMI_D9 - - - - EVENTOUT
122 PH8 - - - - I2C3_SDA OCTOSPIM_P2_IO3 - - - - DCMI_HSYNC - - - - EVENTOUT
123 PH9 - - - - I2C3_SMBA OCTOSPIM_P2_IO4 - - - - DCMI_D0 - - - - EVENTOUT
124 PH10 - - TIM5_CH1 - - OCTOSPIM_P2_IO5 - - - - DCMI_D1 - - - - EVENTOUT
125 PH11 - - TIM5_CH2 - - OCTOSPIM_P2_IO6 - - - - DCMI_D2 - - - - EVENTOUT
126 PH12 - - TIM5_CH3 - - OCTOSPIM_P2_IO7 - - - - DCMI_D3 - - - - EVENTOUT
127 PH13 - - - TIM8_CH1N - - - - - CAN1_TX - - - - - EVENTOUT
128 PH14 - - - TIM8_CH2N - - - - - - DCMI_D4 - - - - EVENTOUT
129 PH15 - - - TIM8_CH3N - OCTOSPIM_P2_IO6 - - - - DCMI_D11 - - - - EVENTOUT
130 PI0 - - TIM5_CH4 OCTOSPIM_P1_IO5 - SPI2_NSS - - - - DCMI_D13 - - - - EVENTOUT
131 PI1 - - - - - SPI2_SCK - - - - DCMI_D8 - - - - EVENTOUT
132 PI2 - - - TIM8_CH4 - SPI2_MISO - - - - DCMI_D9 - - - - EVENTOUT
133 PI3 - - - TIM8_ETR - SPI2_MOSI - - - - DCMI_D10 - - - - EVENTOUT
134 PI4 - - - TIM8_BKIN - - - - - - DCMI_D5 - - - - EVENTOUT
135 PI5 - - - TIM8_CH1 - OCTOSPIM_P2_NCS - - - - DCMI_VSYNC - - - - EVENTOUT
136 PI6 - - - TIM8_CH2 - OCTOSPIM_P2_CLK - - - - DCMI_D6 - - - - EVENTOUT
137 PI7 - - - TIM8_CH3 - - - - - - DCMI_D7 - - - - EVENTOUT
138 PI8 - - - - - OCTOSPIM_P2_NCS - - - - DCMI_D12 - - - - EVENTOUT
139 PI9 - - - - - OCTOSPIM_P2_IO2 - - - CAN1_RX - - - - - EVENTOUT
140 PI10 - - - - - OCTOSPIM_P2_IO1 - - - - - - - - - EVENTOUT
141 PI11 - - - - - OCTOSPIM_P2_IO0 - - - - - - - - - EVENTOUT

View File

@ -25,7 +25,7 @@
import csv
import sys
# Use: parse_af_csf.py Filename.csv -pins-only
# Use: parse_af_csv.py Filename.csv -pins-only
# Designed for use with .csv files from Micropython, or in identical format
# created via Datasheet peripheral tables with a Sheets program.
#
@ -70,6 +70,7 @@ with open(sys.argv[1]) as csv_file:
["SPI", "SCK"],
["SPI", "MOSI"],
["SPI", "MISO"],
["SPI", "NSS"],
["UART", "TX"],
["UART", "RX"],
]
@ -86,22 +87,22 @@ with open(sys.argv[1]) as csv_file:
# Each line is a list of strings
for row in csv_reader:
altfn = 0
pin = row[1]
if len(pin) < 4:
pin = row[0]
if len(pin) < 4: # add additional leading 0 to pin number after port
pin = pin[:2] + "0" + pin[2:]
for col in row:
array_index = 0
# Evaluate the string for every possible todo entry
for item in todo:
evaluate_periph(col, outlist[array_index], item[0], item[1], altfn - 2, pin)
evaluate_periph(col, outlist[array_index], item[0], item[1], altfn - 1, pin)
# UART special case, run again for USART variant
if item[0] == "UART":
evaluate_periph(
col, outlist[array_index], "USART", item[1], altfn - 2, pin
col, outlist[array_index], "USART", item[1], altfn - 1, pin
)
array_index += 1
# TIM special case
evaluate_tim(col, outlist[-1], altfn - 2, pin)
evaluate_tim(col, outlist[-1], altfn - 1, pin)
altfn += 1
line_count += 1
@ -139,10 +140,10 @@ with open(sys.argv[1]) as csv_file:
for row in csv_reader:
altfn = 0
pin = row[1]
pin = row[0]
if len(pin) < 4:
pin = pin[:2] + "0" + pin[2:]
outlist.append([pin, str(ord(row[1][1:2]) - 65), row[1][2:4]])
outlist.append([pin, str(ord(pin[1:2]) - 65), pin[2:4]])
line_count += 1
for line in outlist:
@ -159,4 +160,4 @@ with open(sys.argv[1]) as csv_file:
for line in outlist:
print("extern const mcu_pin_obj_t pin_" + line[0] + ";")
print(f"Processed {line_count} lines.")
print("Processed %d lines." % line_count)

View File

@ -35,6 +35,11 @@
#include "tusb.h"
#if CIRCUITPY_USB_VENDOR
// todo - this doesn't feel like it should be here.
#include "supervisor/memory.h"
#endif
#if CFG_TUD_CDC != 2
#error CFG_TUD_CDC must be exactly 2
#endif
@ -259,3 +264,154 @@ bool common_hal_usb_cdc_enable(bool console, bool data) {
return true;
}
#if CIRCUITPY_USB_VENDOR
#include "usb_vendor_descriptors.h"
#define BOS_TOTAL_LEN (TUD_BOS_DESC_LEN + TUD_BOS_WEBUSB_DESC_LEN + TUD_BOS_MICROSOFT_OS_DESC_LEN)
#define MS_OS_20_DESC_LEN 0xB2
// BOS Descriptor is required for webUSB
uint8_t const desc_bos[] =
{
// total length, number of device caps
TUD_BOS_DESCRIPTOR(BOS_TOTAL_LEN, 2),
// Vendor Code, iLandingPage
TUD_BOS_WEBUSB_DESCRIPTOR(VENDOR_REQUEST_WEBUSB, 1),
// Microsoft OS 2.0 descriptor
TUD_BOS_MS_OS_20_DESCRIPTOR(MS_OS_20_DESC_LEN, VENDOR_REQUEST_MICROSOFT)
};
uint8_t const *tud_descriptor_bos_cb(void) {
return desc_bos;
}
#define MS_OS_20_ITF_NUM_MAGIC 0x5b
#define MS_OS_20_ITF_NUM_OFFSET 22
const uint8_t ms_os_20_descriptor_template[] =
{
// 10 Set header: length, type, windows version, total length
U16_TO_U8S_LE(0x000A), U16_TO_U8S_LE(MS_OS_20_SET_HEADER_DESCRIPTOR), U32_TO_U8S_LE(0x06030000), U16_TO_U8S_LE(MS_OS_20_DESC_LEN),
// 8 Configuration subset header: length, type, configuration index, reserved, configuration total length
U16_TO_U8S_LE(0x0008), U16_TO_U8S_LE(MS_OS_20_SUBSET_HEADER_CONFIGURATION), 0, 0, U16_TO_U8S_LE(MS_OS_20_DESC_LEN - 0x0A),
// 8 Function Subset header: length, type, first interface, reserved, subset length
U16_TO_U8S_LE(0x0008), U16_TO_U8S_LE(MS_OS_20_SUBSET_HEADER_FUNCTION), /* 22 */ MS_OS_20_ITF_NUM_MAGIC, 0, U16_TO_U8S_LE(MS_OS_20_DESC_LEN - 0x0A - 0x08),
// 20 MS OS 2.0 Compatible ID descriptor: length, type, compatible ID, sub compatible ID
U16_TO_U8S_LE(0x0014), U16_TO_U8S_LE(MS_OS_20_FEATURE_COMPATBLE_ID), 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // sub-compatible
// MS OS 2.0 Registry property descriptor: length, type
U16_TO_U8S_LE(MS_OS_20_DESC_LEN - 0x0A - 0x08 - 0x08 - 0x14), U16_TO_U8S_LE(MS_OS_20_FEATURE_REG_PROPERTY),
U16_TO_U8S_LE(0x0007), U16_TO_U8S_LE(0x002A), // wPropertyDataType, wPropertyNameLength and PropertyName "DeviceInterfaceGUIDs\0" in UTF-16
'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, 't', 0x00, 'e', 0x00,
'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, 'U', 0x00, 'I', 0x00, 'D', 0x00, 's', 0x00, 0x00, 0x00,
U16_TO_U8S_LE(0x0050), // wPropertyDataLength
// bPropertyData: “{975F44D9-0D08-43FD-8B3E-127CA8AFFF9D}”.
'{', 0x00, '9', 0x00, '7', 0x00, '5', 0x00, 'F', 0x00, '4', 0x00, '4', 0x00, 'D', 0x00, '9', 0x00, '-', 0x00,
'0', 0x00, 'D', 0x00, '0', 0x00, '8', 0x00, '-', 0x00, '4', 0x00, '3', 0x00, 'F', 0x00, 'D', 0x00, '-', 0x00,
'8', 0x00, 'B', 0x00, '3', 0x00, 'E', 0x00, '-', 0x00, '1', 0x00, '2', 0x00, '7', 0x00, 'C', 0x00, 'A', 0x00,
'8', 0x00, 'A', 0x00, 'F', 0x00, 'F', 0x00, 'F', 0x00, '9', 0x00, 'D', 0x00, '}', 0x00, 0x00, 0x00, 0x00, 0x00
};
TU_VERIFY_STATIC(sizeof(ms_os_20_descriptor_template) == MS_OS_20_DESC_LEN, "Incorrect size");
static const uint8_t usb_vendor_descriptor_template[] = {
// Vendor Descriptor
0x09, // 0 bLength
0x04, // 1 bDescriptorType (Interface)
0xFF, // 2 bInterfaceNumber [SET AT RUNTIME]
#define VENDOR_INTERFACE_INDEX 2
0x00, // 3 bAlternateSetting
0x02, // 4 bNumEndpoints 2
0xFF, // 5 bInterfaceClass: Vendor Specific
0x00, // 6 bInterfaceSubClass: NONE
0x00, // 7 bInterfaceProtocol: NONE
0xFF, // 8 iInterface (String Index)
#define VENDOR_INTERFACE_STRING_INDEX 8
// Vendor OUT Endpoint Descriptor
0x07, // 9 bLength
0x05, // 10 bDescriptorType (Endpoint)
0xFF, // 11 bEndpointAddress (IN/D2H) [SET AT RUNTIME: number]
#define VENDOR_OUT_ENDPOINT_INDEX 11
0x02, // 12 bmAttributes (Bulk)
#if USB_HIGHSPEED
0x00, 0x02, // 13,14 wMaxPacketSize 512
#else
0x40, 0x00, // 13,14 wMaxPacketSize 64
#endif
0x0, // 15 bInterval 0
// Vendor IN Endpoint Descriptor
0x07, // 16 bLength
0x05, // 17 bDescriptorType (Endpoint)
0xFF, // 18 bEndpointAddress (IN/D2H) [SET AT RUNTIME: 0x80 | number]
#define VENDOR_IN_ENDPOINT_INDEX 18
0x02, // 19 bmAttributes (Bulk)
0x40, 0x00, // 20, 21 wMaxPacketSize 64
0x0 // 22 bInterval 0
};
static const char vendor_interface_name[] = USB_INTERFACE_NAME " WebUSB";
bool usb_vendor_enabled(void) {
return usb_cdc_console_enabled();
}
size_t usb_vendor_descriptor_length(void) {
return sizeof(usb_vendor_descriptor_template);
}
static supervisor_allocation *ms_os_20_descriptor_allocation;
size_t vendor_ms_os_20_descriptor_length() {
return sizeof(ms_os_20_descriptor_template);
}
uint8_t const *vendor_ms_os_20_descriptor() {
return (uint8_t *)ms_os_20_descriptor_allocation->ptr;
}
size_t usb_vendor_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *descriptor_counts, uint8_t *current_interface_string) {
if (ms_os_20_descriptor_template[MS_OS_20_ITF_NUM_OFFSET] == MS_OS_20_ITF_NUM_MAGIC) {
ms_os_20_descriptor_allocation =
allocate_memory(align32_size(sizeof(ms_os_20_descriptor_template)),
/*high_address*/ false, /*movable*/ false);
uint8_t *ms_os_20_descriptor_buf = (uint8_t *)ms_os_20_descriptor_allocation->ptr;
memcpy(ms_os_20_descriptor_buf, ms_os_20_descriptor_template, sizeof(ms_os_20_descriptor_template));
ms_os_20_descriptor_buf[MS_OS_20_ITF_NUM_OFFSET] = descriptor_counts->current_interface;
ms_os_20_descriptor_buf[VENDOR_IN_ENDPOINT_INDEX] = 0x80 | descriptor_counts->current_endpoint;
ms_os_20_descriptor_buf[VENDOR_OUT_ENDPOINT_INDEX] = descriptor_counts->current_endpoint;
}
memcpy(descriptor_buf, usb_vendor_descriptor_template, sizeof(usb_vendor_descriptor_template));
descriptor_buf[VENDOR_INTERFACE_INDEX] = descriptor_counts->current_interface;
descriptor_counts->current_interface++;
descriptor_buf[VENDOR_IN_ENDPOINT_INDEX] = 0x80 | descriptor_counts->current_endpoint;
descriptor_counts->num_in_endpoints++;
descriptor_buf[VENDOR_OUT_ENDPOINT_INDEX] = descriptor_counts->current_endpoint;
descriptor_counts->num_out_endpoints++;
descriptor_counts->current_endpoint++;
usb_add_interface_string(*current_interface_string, vendor_interface_name);
descriptor_buf[VENDOR_INTERFACE_STRING_INDEX] = *current_interface_string;
(*current_interface_string)++;
return sizeof(usb_vendor_descriptor_template);
}
#endif

View File

@ -39,4 +39,13 @@ void usb_cdc_set_defaults(void);
size_t usb_cdc_descriptor_length(void);
size_t usb_cdc_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *descriptor_counts, uint8_t *current_interface_string, bool console);
#if CIRCUITPY_USB_VENDOR
bool usb_vendor_enabled(void);
size_t usb_vendor_descriptor_length(void);
size_t usb_vendor_add_descriptor(uint8_t *descriptor_buf, descriptor_counts_t *descriptor_counts, uint8_t *current_interface_string);
size_t vendor_ms_os_20_descriptor_length(void);
uint8_t const *vendor_ms_os_20_descriptor(void);
#endif
#endif /* SHARED_MODULE_USB_CDC___INIT___H */

View File

@ -52,6 +52,10 @@ enum {
+ 1 // hid_report_descriptor_allocation
+ 1 // hid_devices_allocation
#endif
#if CIRCUITPY_USB_VENDOR
+ 1 // usb_vendor_add_descriptor
#endif
,
CIRCUITPY_SUPERVISOR_MOVABLE_ALLOC_COUNT =

View File

@ -54,13 +54,23 @@
#include "tusb.h"
#if CIRCUITPY_USB_VENDOR
#include "usb_vendor_descriptors.h"
// The WebUSB support being conditionally added to this file is based on the
// tinyusb demo examples/device/webusb_serial.
extern const tusb_desc_webusb_url_t desc_webusb_url;
static bool web_serial_connected = false;
#define URL "www.tinyusb.org/examples/webusb-serial"
const tusb_desc_webusb_url_t desc_webusb_url =
{
.bLength = 3 + sizeof(URL) - 1,
.bDescriptorType = 3, // WEBUSB URL type
.bScheme = 1, // 0: http, 1: https
.url = URL
};
#endif
bool usb_enabled(void) {
@ -253,10 +263,11 @@ bool tud_vendor_control_xfer_cb(uint8_t rhport, uint8_t stage, tusb_control_requ
case VENDOR_REQUEST_MICROSOFT:
if (request->wIndex == 7) {
// Get Microsoft OS 2.0 compatible descriptor
// let's just hope the target architecture always has the same endianness
uint16_t total_len;
memcpy(&total_len, desc_ms_os_20 + 8, 2);
memcpy(&total_len, vendor_ms_os_20_descriptor() + 8, 2);
return tud_control_xfer(rhport, request, (void *)desc_ms_os_20, total_len);
return tud_control_xfer(rhport, request, (void *)vendor_ms_os_20_descriptor(), total_len);
} else {
return false;
}

View File

@ -170,6 +170,13 @@ static void usb_build_configuration_descriptor(void) {
}
#endif
#if CIRCUITPY_USB_VENDOR
if (usb_vendor_enabled()) {
total_descriptor_length += usb_vendor_descriptor_length();
}
#endif
// Now we now how big the configuration descriptor will be, so we can allocate space for it.
configuration_descriptor_allocation =
allocate_memory(align32_size(total_descriptor_length),
@ -235,6 +242,13 @@ static void usb_build_configuration_descriptor(void) {
}
#endif
#if CIRCUITPY_USB_VENDOR
if (usb_vendor_enabled()) {
descriptor_buf_remaining += usb_vendor_add_descriptor(
descriptor_buf_remaining, &descriptor_counts, &current_interface_string);
}
#endif
// Now we know how many interfaces have been used.
configuration_descriptor[CONFIG_NUM_INTERFACES_INDEX] = descriptor_counts.current_interface;

View File

@ -0,0 +1,39 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* 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 USB_DESCRIPTORS_H_
#define USB_DESCRIPTORS_H_
#include <stdint.h>
enum
{
VENDOR_REQUEST_WEBUSB = 1,
VENDOR_REQUEST_MICROSOFT = 2
};
size_t vendor_ms_os_20_descriptor_length(void);
uint8_t const *vendor_ms_os_20_descriptor(void);
#endif /* USB_DESCRIPTORS_H_ */