mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: port for STM32L4+ processor
Added support for stm32l4+ processor - Added scripts for hwdef generation - Tested in custom hardware prototype (stm32l4r5vit6) - Tested all peripherals and auto pilot modes.
This commit is contained in:
parent
880e6366bd
commit
ae9e15ade5
|
@ -265,8 +265,8 @@ void AnalogIn::init()
|
|||
} else {
|
||||
adcgrpcfg.sqr[2] |= chan << (6*(i-9));
|
||||
}
|
||||
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32G4) || defined(STM32L4)
|
||||
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
#if defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_640P5 << (3*(chan%10));
|
||||
#else
|
||||
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_601P5 << (3*(chan%10));
|
||||
|
|
|
@ -205,7 +205,7 @@ void GPIO::pinMode(uint8_t pin, uint8_t output)
|
|||
return;
|
||||
}
|
||||
g->mode = output?PAL_MODE_OUTPUT_PUSHPULL:PAL_MODE_INPUT;
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
if (g->mode == PAL_MODE_OUTPUT_PUSHPULL) {
|
||||
// retain OPENDRAIN if already set
|
||||
iomode_t old_mode = palReadLineMode(g->pal_line);
|
||||
|
@ -550,7 +550,7 @@ bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const
|
|||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
|
||||
// allow for save and restore of pin settings
|
||||
bool GPIO::get_mode(uint8_t pin, uint32_t &mode)
|
||||
|
|
|
@ -94,7 +94,7 @@ public:
|
|||
*/
|
||||
static ioline_t resolve_alt_config(ioline_t base, PERIPH_TYPE ptype, uint8_t instance);
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
// allow for save and restore of pin settings
|
||||
bool get_mode(uint8_t pin, uint32_t &mode) override;
|
||||
void set_mode(uint8_t pin, uint32_t mode) override;
|
||||
|
|
|
@ -76,6 +76,14 @@ I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)];
|
|||
#define HAL_I2C_L4_400_TIMINGR 0x00702991
|
||||
#endif
|
||||
|
||||
#ifndef HAL_I2C_L4PLUS_100_TIMINGR
|
||||
#define HAL_I2C_L4PLUS_100_TIMINGR 0x307075B1
|
||||
#endif
|
||||
|
||||
#ifndef HAL_I2C_L4PLUS_400_TIMINGR
|
||||
#define HAL_I2C_L4PLUS_400_TIMINGR 0x00501BFF
|
||||
#endif
|
||||
|
||||
#ifndef HAL_I2C_G4_100_TIMINGR
|
||||
#define HAL_I2C_G4_100_TIMINGR 0x60505F8C
|
||||
#endif
|
||||
|
@ -223,6 +231,15 @@ I2CDeviceManager::I2CDeviceManager(void)
|
|||
businfo[i].i2ccfg.timingr = HAL_I2C_L4_400_TIMINGR;
|
||||
businfo[i].busclock = 400000;
|
||||
}
|
||||
#elif defined(STM32L4PLUS)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_L4PLUS_100_TIMINGR;
|
||||
businfo[i].busclock = 100000;
|
||||
} else {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_L4PLUS_400_TIMINGR;
|
||||
businfo[i].busclock = 400000;
|
||||
}
|
||||
|
||||
#elif defined(STM32G4)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_G4_100_TIMINGR;
|
||||
|
@ -255,7 +272,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u
|
|||
asprintf(&pname, "I2C:%u:%02x",
|
||||
(unsigned)busnum, (unsigned)address);
|
||||
if (bus_clock < bus.busclock) {
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
if (bus_clock <= 100000) {
|
||||
bus.i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
bus.busclock = 100000;
|
||||
|
@ -302,7 +319,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
if (_use_smbus) {
|
||||
bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN;
|
||||
} else {
|
||||
|
|
|
@ -38,6 +38,12 @@ using namespace ChibiOS;
|
|||
#define HAVE_USB_SERIAL
|
||||
#endif
|
||||
|
||||
#if defined (STM32L4PLUS)
|
||||
#ifndef USART_CR1_RXNEIE
|
||||
#define USART_CR1_RXNEIE USART_CR1_RXNEIE_RXFNEIE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
extern ChibiOS::UARTDriver uart_io;
|
||||
#endif
|
||||
|
@ -383,7 +389,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
(void *)this);
|
||||
osalDbgAssert(rxdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
|
@ -482,7 +488,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
|||
(void *)this);
|
||||
osalDbgAssert(txdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
|
@ -531,7 +537,7 @@ void UARTDriver::rx_irq_cb(void* self)
|
|||
#if defined(STM32F7) || defined(STM32H7)
|
||||
//disable dma, triggering DMA transfer complete interrupt
|
||||
uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
|
||||
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
//disable dma, triggering DMA transfer complete interrupt
|
||||
dmaStreamDisable(uart_drv->rxdma);
|
||||
uart_drv->rxdma->channel->CCR &= ~STM32_DMA_CR_EN;
|
||||
|
@ -1186,7 +1192,7 @@ void UARTDriver::_rx_timer_tick(void)
|
|||
//Check if DMA is enabled
|
||||
//if not, it might be because the DMA interrupt was silenced
|
||||
//let's handle that here so that we can continue receiving
|
||||
#if defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
bool enabled = (rxdma->channel->CCR & STM32_DMA_CR_EN);
|
||||
#else
|
||||
bool enabled = (rxdma->stream->CR & STM32_DMA_CR_EN);
|
||||
|
@ -1608,7 +1614,7 @@ bool UARTDriver::set_options(uint16_t options)
|
|||
// Check flow control, might have to disable if RTS line is gone
|
||||
set_flow_control(_flow_control);
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
// F7 has built-in support for inversion in all uarts
|
||||
ioline_t rx_line = (options & OPTION_SWAP)?atx_line:arx_line;
|
||||
ioline_t tx_line = (options & OPTION_SWAP)?arx_line:atx_line;
|
||||
|
|
|
@ -0,0 +1,48 @@
|
|||
# MCU class and specific type
|
||||
MCU STM32L4xx STM32L4R5xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1090
|
||||
|
||||
USB_STRING_MANUFACTURER "Dheeran labs"
|
||||
USB_STRING_PRODUCT "PixFlamingo"
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
APP_START_OFFSET_KB 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
PE7 LED_BOOTLOADER OUTPUT LOW
|
||||
PB2 LED_ACTIVITY OUTPUT
|
||||
define HAL_LED_ON 1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
PA11 USB_OTG_FS_DM OTG1
|
||||
PA12 USB_OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# location of application code
|
||||
FLASH_BOOTLOADER_LOAD_KB 20
|
||||
|
||||
# bootloader loads at start of flash
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PD0 IMU1_CS CS
|
||||
PE0 GYRO_CS CS
|
||||
PB5 BARO_CS CS
|
||||
PD7 MAG_CS CS
|
|
@ -0,0 +1,190 @@
|
|||
|
||||
# MCU class and specific type
|
||||
MCU STM32L4xx STM32L4R5xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1090
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
USB_STRING_MANUFACTURER "Dheeran labs"
|
||||
USB_STRING_PRODUCT "PixFlamingo"
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
FLASH_RESERVE_START_KB 28
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART3 USART1 UART4
|
||||
|
||||
PC1 BATT_VOLTAGE_SENS ADC1
|
||||
PC0 BATT_CURRENT_SENS ADC1
|
||||
PA4 VDD_5V_SENS ADC1 SCALE(2)
|
||||
|
||||
# SPI1 is fram bus
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
PA11 USB_OTG_FS_DM OTG1
|
||||
PA12 USB_OTG_FS_DP OTG1
|
||||
|
||||
# USART3 serial3 telem1
|
||||
PC4 USART3_TX USART3
|
||||
PC5 USART3_RX USART3
|
||||
PB13 USART3_CTS USART3
|
||||
PB14 USART3_RTS USART3
|
||||
|
||||
# USART1 serial1 telem2
|
||||
PB6 USART1_TX USART1
|
||||
PB7 USART1_RX USART1
|
||||
PB4 USART1_CTS USART1
|
||||
PB3 USART1_RTS USART1
|
||||
|
||||
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
define HAL_USE_SERIAL TRUE
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# PWM output for buzzer
|
||||
|
||||
PA15 BUZZER OUTPUT GPIO(80) LOW
|
||||
define HAL_BUZZER_PIN 80
|
||||
define HAL_BUZZER_ON 1
|
||||
define HAL_BUZZER_OFF 0
|
||||
|
||||
PE2 BOOT1 INPUT
|
||||
PD9 VDD_BRICK_VALID INPUT PULLDOWN
|
||||
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
# SPI2 is for sensors
|
||||
PD1 SPI2_SCK SPI2
|
||||
PD3 SPI2_MISO SPI2
|
||||
PD4 SPI2_MOSI SPI2
|
||||
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
PD0 IMU1_CS CS
|
||||
PE0 GYRO_CS CS
|
||||
PB5 BARO_CS CS
|
||||
PD7 MAG_CS CS
|
||||
|
||||
# This defines more ADC inputs.
|
||||
PC2 AUX_POWER ADC1 SCALE(1)
|
||||
PC3 AUX_ADC2 ADC1 SCALE(1)
|
||||
|
||||
PD10 VBUS_VALID INPUT PULLDOWN
|
||||
PB0 RSSI_IN ADC1 SCALE(1)
|
||||
PE12 LED_SAFETY OUTPUT
|
||||
PE15 SAFETY_IN INPUT PULLDOWN
|
||||
PC14 VDD_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
#PD6 RCININT PULLDOWN LOW # also USART6_RX for serial RC
|
||||
PC7 SBUS_INV OUTPUT LOW
|
||||
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
|
||||
PE5 IMU1_DRDY INPUT
|
||||
PE4 MAG_DRDY INPUT
|
||||
PE6 GYRO_DRDY INPUT
|
||||
|
||||
PC13 VDD_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
|
||||
PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW
|
||||
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
||||
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
PB15 TIM15_CH2 TIM15 PWM(9) GPIO(59)
|
||||
|
||||
|
||||
# SPI device table.
|
||||
|
||||
SPIDEV icm42670 SPI2 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV lis3mdl SPI2 DEVID5 MAG_CS MODE3 500*KHZ 500*KHZ
|
||||
SPIDEV lsm9ds0_g SPI2 DEVID4 GYRO_CS MODE3 11*MHZ 11*MHZ
|
||||
|
||||
# enable FAT filesystem
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
|
||||
# pixracer has 3 LEDs, Red, Green, Blue
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# LED setup for PixracerLED driver
|
||||
PE8 LED_RED OUTPUT GPIO(0)
|
||||
PE7 LED_GREEN OUTPUT GPIO(1)
|
||||
PB2 LED_BLUE OUTPUT GPIO(2)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
|
||||
# battery setup
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 2
|
||||
define HAL_BATT_CURR_PIN 1
|
||||
define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
DMA_PRIORITY S*
|
||||
|
||||
define STORAGE_FLASH_PAGE 5
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
|
||||
# two IMUs
|
||||
IMU Invensensev3 SPI:icm42670 ROTATION_YAW_270
|
||||
IMU LSM9DS0 SPI:lsm9ds0_g SPI:lsm9ds0_am ROTATION_ROLL_180 ROTATION_ROLL_180_YAW_270 ROTATION_PITCH_180
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
COMPASS LIS3MDL SPI:lis3mdl false ROTATION_NONE
|
||||
|
||||
# also probe all types of external I2C compasses
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
define STM32_I2C_USE_DMA FALSE
|
||||
# one barometer
|
||||
BARO MS56XX SPI:ms5611
|
|
@ -0,0 +1,490 @@
|
|||
#MicroXplorer Configuration settings - do not modify
|
||||
ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_15
|
||||
ADC1.ClockPrescaler=ADC_CLOCK_ASYNC_DIV4
|
||||
ADC1.IPParameters=Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,OffsetNumber-0\#ChannelRegularConversion,NbrOfConversionFlag,SingleDiff-0\#ChannelRegularConversion,master,ClockPrescaler
|
||||
ADC1.NbrOfConversionFlag=1
|
||||
ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.Rank-0\#ChannelRegularConversion=1
|
||||
ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5
|
||||
ADC1.SingleDiff-0\#ChannelRegularConversion=ADC_DIFFERENTIAL_ENDED
|
||||
ADC1.master=1
|
||||
CAN1.BS1=CAN_BS1_7TQ
|
||||
CAN1.CalculateBaudRate=833333
|
||||
CAN1.CalculateTimeBit=1200
|
||||
CAN1.CalculateTimeQuantum=133.33333333333334
|
||||
CAN1.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,BS1
|
||||
File.Version=6
|
||||
GPIO.groupedBy=
|
||||
I2C2.CustomTiming=Enabled
|
||||
I2C2.I2C_Speed_Mode=I2C_Standard
|
||||
I2C2.IPParameters=Timing,I2C_Speed_Mode,Speed,CustomTiming
|
||||
I2C2.Speed=100
|
||||
I2C2.Timing=0x00B03FDB
|
||||
KeepUserPlacement=false
|
||||
Mcu.CPN=STM32L4R5VIT6
|
||||
Mcu.Family=STM32L4
|
||||
Mcu.IP0=ADC1
|
||||
Mcu.IP1=CAN1
|
||||
Mcu.IP10=TIM1
|
||||
Mcu.IP11=TIM2
|
||||
Mcu.IP12=TIM3
|
||||
Mcu.IP13=TIM4
|
||||
Mcu.IP14=UART4
|
||||
Mcu.IP15=USART1
|
||||
Mcu.IP16=USART2
|
||||
Mcu.IP17=USART3
|
||||
Mcu.IP18=USB_OTG_FS
|
||||
Mcu.IP2=I2C2
|
||||
Mcu.IP3=LPUART1
|
||||
Mcu.IP4=NVIC
|
||||
Mcu.IP5=RCC
|
||||
Mcu.IP6=SDMMC1
|
||||
Mcu.IP7=SPI1
|
||||
Mcu.IP8=SPI2
|
||||
Mcu.IP9=SYS
|
||||
Mcu.IPNb=19
|
||||
Mcu.Name=STM32L4R5V(G-I)Tx
|
||||
Mcu.Package=LQFP100
|
||||
Mcu.Pin0=PE3
|
||||
Mcu.Pin1=PE4
|
||||
Mcu.Pin10=PC2
|
||||
Mcu.Pin11=PC3
|
||||
Mcu.Pin12=PA0
|
||||
Mcu.Pin13=PA1
|
||||
Mcu.Pin14=PA2
|
||||
Mcu.Pin15=PA3
|
||||
Mcu.Pin16=PA4
|
||||
Mcu.Pin17=PA5
|
||||
Mcu.Pin18=PA6
|
||||
Mcu.Pin19=PA7
|
||||
Mcu.Pin2=PE5
|
||||
Mcu.Pin20=PC4
|
||||
Mcu.Pin21=PC5
|
||||
Mcu.Pin22=PB0
|
||||
Mcu.Pin23=PB1
|
||||
Mcu.Pin24=PB2
|
||||
Mcu.Pin25=PE7
|
||||
Mcu.Pin26=PE8
|
||||
Mcu.Pin27=PE9
|
||||
Mcu.Pin28=PE10
|
||||
Mcu.Pin29=PE11
|
||||
Mcu.Pin3=PE6
|
||||
Mcu.Pin30=PE13
|
||||
Mcu.Pin31=PE14
|
||||
Mcu.Pin32=PB10
|
||||
Mcu.Pin33=PB11
|
||||
Mcu.Pin34=PB13
|
||||
Mcu.Pin35=PB14
|
||||
Mcu.Pin36=PB15
|
||||
Mcu.Pin37=PD9
|
||||
Mcu.Pin38=PD10
|
||||
Mcu.Pin39=PD12
|
||||
Mcu.Pin4=PC13
|
||||
Mcu.Pin40=PD13
|
||||
Mcu.Pin41=PD14
|
||||
Mcu.Pin42=PD15
|
||||
Mcu.Pin43=PC6
|
||||
Mcu.Pin44=PC7
|
||||
Mcu.Pin45=PC8
|
||||
Mcu.Pin46=PC9
|
||||
Mcu.Pin47=PA9
|
||||
Mcu.Pin48=PA10
|
||||
Mcu.Pin49=PA11
|
||||
Mcu.Pin5=PC14-OSC32_IN (PC14)
|
||||
Mcu.Pin50=PA12
|
||||
Mcu.Pin51=PA13 (JTMS/SWDIO)
|
||||
Mcu.Pin52=PA14 (JTCK/SWCLK)
|
||||
Mcu.Pin53=PA15 (JTDI)
|
||||
Mcu.Pin54=PC10
|
||||
Mcu.Pin55=PC11
|
||||
Mcu.Pin56=PC12
|
||||
Mcu.Pin57=PD0
|
||||
Mcu.Pin58=PD1
|
||||
Mcu.Pin59=PD2
|
||||
Mcu.Pin6=PH0-OSC_IN (PH0)
|
||||
Mcu.Pin60=PD3
|
||||
Mcu.Pin61=PD4
|
||||
Mcu.Pin62=PD5
|
||||
Mcu.Pin63=PD6
|
||||
Mcu.Pin64=PD7
|
||||
Mcu.Pin65=PB3 (JTDO/TRACESWO)
|
||||
Mcu.Pin66=PB4 (NJTRST)
|
||||
Mcu.Pin67=PB5
|
||||
Mcu.Pin68=PB6
|
||||
Mcu.Pin69=PB7
|
||||
Mcu.Pin7=PH1-OSC_OUT (PH1)
|
||||
Mcu.Pin70=PB8
|
||||
Mcu.Pin71=PB9
|
||||
Mcu.Pin72=PE0
|
||||
Mcu.Pin73=VP_SYS_VS_Systick
|
||||
Mcu.Pin8=PC0
|
||||
Mcu.Pin9=PC1
|
||||
Mcu.PinsNb=74
|
||||
Mcu.ThirdPartyNb=0
|
||||
Mcu.UserConstants=
|
||||
Mcu.UserName=STM32L4R5VITx
|
||||
MxCube.Version=6.6.1
|
||||
MxDb.Version=DB.6.0.60
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.ForceEnableDMAVector=true
|
||||
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
|
||||
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
|
||||
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
PA0.Locked=true
|
||||
PA0.Mode=Asynchronous
|
||||
PA0.Signal=UART4_TX
|
||||
PA1.Locked=true
|
||||
PA1.Mode=Asynchronous
|
||||
PA1.Signal=UART4_RX
|
||||
PA10.Mode=OTG/Dual_Role_Device
|
||||
PA10.Signal=USB_OTG_FS_ID
|
||||
PA11.Locked=true
|
||||
PA11.Mode=OTG/Dual_Role_Device
|
||||
PA11.Signal=USB_OTG_FS_DM
|
||||
PA12.Locked=true
|
||||
PA12.Mode=OTG/Dual_Role_Device
|
||||
PA12.Signal=USB_OTG_FS_DP
|
||||
PA13\ (JTMS/SWDIO).Locked=true
|
||||
PA13\ (JTMS/SWDIO).Signal=SYS_JTMS-SWDIO
|
||||
PA14\ (JTCK/SWCLK).Locked=true
|
||||
PA14\ (JTCK/SWCLK).Signal=SYS_JTCK-SWCLK
|
||||
PA15\ (JTDI).Locked=true
|
||||
PA15\ (JTDI).Signal=S_TIM2_CH1
|
||||
PA2.Locked=true
|
||||
PA2.Mode=Asynchronous
|
||||
PA2.Signal=LPUART1_TX
|
||||
PA3.Locked=true
|
||||
PA3.Mode=Asynchronous
|
||||
PA3.Signal=LPUART1_RX
|
||||
PA4.Locked=true
|
||||
PA4.Signal=GPIO_Output
|
||||
PA5.Locked=true
|
||||
PA5.Mode=Full_Duplex_Master
|
||||
PA5.Signal=SPI1_SCK
|
||||
PA6.Locked=true
|
||||
PA6.Mode=Full_Duplex_Master
|
||||
PA6.Signal=SPI1_MISO
|
||||
PA7.Locked=true
|
||||
PA7.Mode=Full_Duplex_Master
|
||||
PA7.Signal=SPI1_MOSI
|
||||
PA9.Locked=true
|
||||
PA9.Mode=Activate_VBUS
|
||||
PA9.Signal=USB_OTG_FS_VBUS
|
||||
PB0.Locked=true
|
||||
PB0.Signal=ADCx_IN15
|
||||
PB1.Signal=ADCx_IN16
|
||||
PB10.Locked=true
|
||||
PB10.Mode=I2C
|
||||
PB10.Signal=I2C2_SCL
|
||||
PB11.Locked=true
|
||||
PB11.Mode=I2C
|
||||
PB11.Signal=I2C2_SDA
|
||||
PB13.Locked=true
|
||||
PB13.Mode=CTS_RTS
|
||||
PB13.Signal=USART3_CTS
|
||||
PB14.Locked=true
|
||||
PB14.Mode=CTS_RTS
|
||||
PB14.Signal=USART3_RTS
|
||||
PB15.Locked=true
|
||||
PB15.Signal=S_TIM15_CH2
|
||||
PB2.Locked=true
|
||||
PB2.Signal=GPIO_Output
|
||||
PB3\ (JTDO/TRACESWO).Locked=true
|
||||
PB3\ (JTDO/TRACESWO).Mode=CTS_RTS
|
||||
PB3\ (JTDO/TRACESWO).Signal=USART1_RTS
|
||||
PB4\ (NJTRST).Locked=true
|
||||
PB4\ (NJTRST).Mode=CTS_RTS
|
||||
PB4\ (NJTRST).Signal=USART1_CTS
|
||||
PB5.Locked=true
|
||||
PB5.Signal=GPIO_Output
|
||||
PB6.Locked=true
|
||||
PB6.Mode=Asynchronous
|
||||
PB6.Signal=USART1_TX
|
||||
PB7.Locked=true
|
||||
PB7.Mode=Asynchronous
|
||||
PB7.Signal=USART1_RX
|
||||
PB8.Locked=true
|
||||
PB8.Mode=CAN_Activate
|
||||
PB8.Signal=CAN1_RX
|
||||
PB9.Locked=true
|
||||
PB9.Mode=CAN_Activate
|
||||
PB9.Signal=CAN1_TX
|
||||
PC0.Signal=ADCx_IN1
|
||||
PC1.Signal=ADCx_IN2
|
||||
PC10.Locked=true
|
||||
PC10.Mode=SD_4_bits_Wide_bus
|
||||
PC10.Signal=SDMMC1_D2
|
||||
PC11.Locked=true
|
||||
PC11.Mode=SD_4_bits_Wide_bus
|
||||
PC11.Signal=SDMMC1_D3
|
||||
PC12.Locked=true
|
||||
PC12.Mode=SD_4_bits_Wide_bus
|
||||
PC12.Signal=SDMMC1_CK
|
||||
PC13.Locked=true
|
||||
PC13.Signal=GPIO_Output
|
||||
PC14-OSC32_IN\ (PC14).Locked=true
|
||||
PC14-OSC32_IN\ (PC14).Signal=GPIO_Output
|
||||
PC2.Locked=true
|
||||
PC2.Signal=ADCx_IN3
|
||||
PC3.Locked=true
|
||||
PC3.Signal=ADCx_IN4
|
||||
PC4.Locked=true
|
||||
PC4.Mode=Asynchronous
|
||||
PC4.Signal=USART3_TX
|
||||
PC5.Locked=true
|
||||
PC5.Mode=Asynchronous
|
||||
PC5.Signal=USART3_RX
|
||||
PC6.Locked=true
|
||||
PC6.Signal=S_TIM8_CH1
|
||||
PC7.Locked=true
|
||||
PC7.Signal=GPIO_Output
|
||||
PC8.Locked=true
|
||||
PC8.Mode=SD_4_bits_Wide_bus
|
||||
PC8.Signal=SDMMC1_D0
|
||||
PC9.Locked=true
|
||||
PC9.Mode=SD_4_bits_Wide_bus
|
||||
PC9.Signal=SDMMC1_D1
|
||||
PD0.Locked=true
|
||||
PD0.Signal=GPIO_Output
|
||||
PD1.Locked=true
|
||||
PD1.Mode=Full_Duplex_Master
|
||||
PD1.Signal=SPI2_SCK
|
||||
PD10.Locked=true
|
||||
PD10.Signal=GPIO_Output
|
||||
PD12.Locked=true
|
||||
PD12.Signal=S_TIM4_CH1
|
||||
PD13.Locked=true
|
||||
PD13.Signal=S_TIM4_CH2
|
||||
PD14.Locked=true
|
||||
PD14.Signal=S_TIM4_CH3
|
||||
PD15.Locked=true
|
||||
PD15.Signal=S_TIM4_CH4
|
||||
PD2.Locked=true
|
||||
PD2.Mode=SD_4_bits_Wide_bus
|
||||
PD2.Signal=SDMMC1_CMD
|
||||
PD3.Locked=true
|
||||
PD3.Mode=Full_Duplex_Master
|
||||
PD3.Signal=SPI2_MISO
|
||||
PD4.Locked=true
|
||||
PD4.Mode=Full_Duplex_Master
|
||||
PD4.Signal=SPI2_MOSI
|
||||
PD5.Locked=true
|
||||
PD5.Mode=Asynchronous
|
||||
PD5.Signal=USART2_TX
|
||||
PD6.Locked=true
|
||||
PD6.Mode=Asynchronous
|
||||
PD6.Signal=USART2_RX
|
||||
PD7.Locked=true
|
||||
PD7.Signal=GPIO_Output
|
||||
PD9.Locked=true
|
||||
PD9.Signal=GPIO_Output
|
||||
PE0.Locked=true
|
||||
PE0.Signal=GPIO_Output
|
||||
PE10.Locked=true
|
||||
PE10.Signal=GPIO_Output
|
||||
PE11.Locked=true
|
||||
PE11.Signal=S_TIM1_CH2
|
||||
PE13.Locked=true
|
||||
PE13.Signal=S_TIM1_CH3
|
||||
PE14.Locked=true
|
||||
PE14.Signal=S_TIM1_CH4
|
||||
PE3.Signal=S_TIM3_CH1
|
||||
PE4.Locked=true
|
||||
PE4.Signal=S_TIM3_CH2
|
||||
PE5.Signal=S_TIM3_CH3
|
||||
PE6.Signal=S_TIM3_CH4
|
||||
PE7.Locked=true
|
||||
PE7.Signal=GPIO_Output
|
||||
PE8.Locked=true
|
||||
PE8.Signal=GPIO_Output
|
||||
PE9.Locked=true
|
||||
PE9.Signal=S_TIM1_CH1
|
||||
PH0-OSC_IN\ (PH0).Mode=HSE-External-Oscillator
|
||||
PH0-OSC_IN\ (PH0).Signal=RCC_OSC_IN
|
||||
PH1-OSC_OUT\ (PH1).Mode=HSE-External-Oscillator
|
||||
PH1-OSC_OUT\ (PH1).Signal=RCC_OSC_OUT
|
||||
PinOutPanel.RotationAngle=0
|
||||
ProjectManager.AskForMigrate=true
|
||||
ProjectManager.BackupPrevious=false
|
||||
ProjectManager.CompilerOptimize=6
|
||||
ProjectManager.ComputerToolchain=false
|
||||
ProjectManager.CoupleFile=false
|
||||
ProjectManager.CustomerFirmwarePackage=
|
||||
ProjectManager.DefaultFWLocation=true
|
||||
ProjectManager.DeletePrevious=true
|
||||
ProjectManager.DeviceId=STM32L4R5VITx
|
||||
ProjectManager.FirmwarePackage=STM32Cube FW_L4 V1.17.2
|
||||
ProjectManager.FreePins=false
|
||||
ProjectManager.HalAssertFull=false
|
||||
ProjectManager.HeapSize=0x200
|
||||
ProjectManager.KeepUserCode=true
|
||||
ProjectManager.LastFirmware=true
|
||||
ProjectManager.LibraryCopy=0
|
||||
ProjectManager.MainLocation=Core/Src
|
||||
ProjectManager.NoMain=false
|
||||
ProjectManager.PreviousToolchain=
|
||||
ProjectManager.ProjectBuild=false
|
||||
ProjectManager.ProjectFileName=flamingo_written.ioc
|
||||
ProjectManager.ProjectName=flamingo_written
|
||||
ProjectManager.RegisterCallBack=
|
||||
ProjectManager.StackSize=0x400
|
||||
ProjectManager.TargetToolchain=EWARM
|
||||
ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UnderRoot=false
|
||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN1_Init-CAN1-false-HAL-true,4-MX_TIM3_Init-TIM3-false-HAL-true,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_I2C2_Init-I2C2-false-HAL-true,7-MX_LPUART1_UART_Init-LPUART1-false-HAL-true,8-MX_UART4_Init-UART4-false-HAL-true,9-MX_USART1_UART_Init-USART1-false-HAL-true,10-MX_USART2_UART_Init-USART2-false-HAL-true,11-MX_USART3_UART_Init-USART3-false-HAL-true,12-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,13-MX_SPI1_Init-SPI1-false-HAL-true,14-MX_SPI2_Init-SPI2-false-HAL-true,15-MX_TIM1_Init-TIM1-false-HAL-true,16-MX_TIM2_Init-TIM2-false-HAL-true,17-MX_TIM4_Init-TIM4-false-HAL-true,18-MX_USB_OTG_FS_USB_Init-USB_OTG_FS-false-HAL-true
|
||||
RCC.ADCFreq_Value=48000000
|
||||
RCC.AHBFreq_Value=120000000
|
||||
RCC.APB1Freq_Value=120000000
|
||||
RCC.APB1TimFreq_Value=120000000
|
||||
RCC.APB2Freq_Value=120000000
|
||||
RCC.APB2TimFreq_Value=120000000
|
||||
RCC.CRSFreq_Value=48000000
|
||||
RCC.CortexFreq_Value=120000000
|
||||
RCC.DFSDMFreq_Value=120000000
|
||||
RCC.FCLKCortexFreq_Value=120000000
|
||||
RCC.FLatency-AdvancedSettings=FLASH_LATENCY_5
|
||||
RCC.FamilyName=M
|
||||
RCC.HCLKFreq_Value=120000000
|
||||
RCC.HSE_VALUE=24000000
|
||||
RCC.HSI48_VALUE=48000000
|
||||
RCC.HSI_VALUE=16000000
|
||||
RCC.I2C1Freq_Value=120000000
|
||||
RCC.I2C2Freq_Value=120000000
|
||||
RCC.I2C3Freq_Value=120000000
|
||||
RCC.I2C4Freq_Value=120000000
|
||||
RCC.IPParameters=ADCFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,DFSDMFreq_Value,FCLKCortexFreq_Value,FLatency-AdvancedSettings,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,LCDTFTFreq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPUART1CLockSelection,LPUART1Freq_Value,LSCOPinFreq_Value,LSE_VALUE,LSI_VALUE,MCO1PinFreq_Value,MSI_VALUE,OCTOSPIMFreq_Value,PLLM1,PLLM2,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSAI1N,PLLSAI1PoutputFreq_Value,PLLSAI1QoutputFreq_Value,PLLSAI1RoutputFreq_Value,PLLSAI2PoutputFreq_Value,PLLSAI2QoutputFreq_Value,PLLSAI2RoutputFreq_Value,PLLSourceVirtual,PWREXT_OverDrive,PWRFreq_Value,RCC_TIM_PRescaler_Selection,RNGFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMCFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4CLockSelection,UART4Freq_Value,UART5Freq_Value,USART1CLockSelection,USART1Freq_Value,USART2CLockSelection,USART2Freq_Value,USART3CLockSelection,USART3Freq_Value,USBFreq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAI1OutputFreq_Value,VCOSAI2OutputFreq_Value
|
||||
RCC.LCDTFTFreq_Value=48000000
|
||||
RCC.LPTIM1Freq_Value=120000000
|
||||
RCC.LPTIM2Freq_Value=120000000
|
||||
RCC.LPUART1CLockSelection=RCC_LPUART1CLKSOURCE_SYSCLK
|
||||
RCC.LPUART1Freq_Value=120000000
|
||||
RCC.LSCOPinFreq_Value=32000
|
||||
RCC.LSE_VALUE=32768
|
||||
RCC.LSI_VALUE=32000
|
||||
RCC.MCO1PinFreq_Value=120000000
|
||||
RCC.MSI_VALUE=4000000
|
||||
RCC.OCTOSPIMFreq_Value=120000000
|
||||
RCC.PLLM1=3
|
||||
RCC.PLLM2=3
|
||||
RCC.PLLN=30
|
||||
RCC.PLLPoutputFreq_Value=120000000
|
||||
RCC.PLLQoutputFreq_Value=120000000
|
||||
RCC.PLLRCLKFreq_Value=120000000
|
||||
RCC.PLLSAI1N=12
|
||||
RCC.PLLSAI1PoutputFreq_Value=48000000
|
||||
RCC.PLLSAI1QoutputFreq_Value=48000000
|
||||
RCC.PLLSAI1RoutputFreq_Value=48000000
|
||||
RCC.PLLSAI2PoutputFreq_Value=96000000
|
||||
RCC.PLLSAI2QoutputFreq_Value=96000000
|
||||
RCC.PLLSAI2RoutputFreq_Value=96000000
|
||||
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
|
||||
RCC.PWREXT_OverDrive=PWREXT_OverDrive_DESACTIVATED
|
||||
RCC.PWRFreq_Value=120000000
|
||||
RCC.RCC_TIM_PRescaler_Selection=RCC_TIMPRES_DESACTIVATED
|
||||
RCC.RNGFreq_Value=48000000
|
||||
RCC.SAI1Freq_Value=48000000
|
||||
RCC.SAI2Freq_Value=48000000
|
||||
RCC.SDMMCFreq_Value=120000000
|
||||
RCC.SYSCLKFreq_VALUE=120000000
|
||||
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
|
||||
RCC.UART4CLockSelection=RCC_UART4CLKSOURCE_SYSCLK
|
||||
RCC.UART4Freq_Value=120000000
|
||||
RCC.UART5Freq_Value=120000000
|
||||
RCC.USART1CLockSelection=RCC_USART1CLKSOURCE_SYSCLK
|
||||
RCC.USART1Freq_Value=120000000
|
||||
RCC.USART2CLockSelection=RCC_USART2CLKSOURCE_SYSCLK
|
||||
RCC.USART2Freq_Value=120000000
|
||||
RCC.USART3CLockSelection=RCC_USART3CLKSOURCE_SYSCLK
|
||||
RCC.USART3Freq_Value=120000000
|
||||
RCC.USBFreq_Value=48000000
|
||||
RCC.VCOInput2Freq_Value=8000000
|
||||
RCC.VCOInput3Freq_Value=24000000
|
||||
RCC.VCOInputFreq_Value=8000000
|
||||
RCC.VCOOutputFreq_Value=240000000
|
||||
RCC.VCOSAI1OutputFreq_Value=96000000
|
||||
RCC.VCOSAI2OutputFreq_Value=192000000
|
||||
SH.ADCx_IN1.0=ADC1_IN1,IN1-Single-Ended
|
||||
SH.ADCx_IN1.ConfNb=1
|
||||
SH.ADCx_IN15.0=ADC1_IN15,IN15-Differential
|
||||
SH.ADCx_IN15.ConfNb=1
|
||||
SH.ADCx_IN16.0=ADC1_IN16,IN15-Differential
|
||||
SH.ADCx_IN16.ConfNb=1
|
||||
SH.ADCx_IN2.0=ADC1_IN2,IN2-Single-Ended
|
||||
SH.ADCx_IN2.ConfNb=1
|
||||
SH.ADCx_IN3.0=ADC1_IN3,IN3-Single-Ended
|
||||
SH.ADCx_IN3.ConfNb=1
|
||||
SH.ADCx_IN4.0=ADC1_IN4
|
||||
SH.ADCx_IN4.ConfNb=1
|
||||
SH.S_TIM15_CH2.0=TIM15_CH2
|
||||
SH.S_TIM15_CH2.ConfNb=1
|
||||
SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM1_CH1.ConfNb=1
|
||||
SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
|
||||
SH.S_TIM1_CH2.ConfNb=1
|
||||
SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
|
||||
SH.S_TIM1_CH3.ConfNb=1
|
||||
SH.S_TIM1_CH4.0=TIM1_CH4,PWM Generation4 CH4
|
||||
SH.S_TIM1_CH4.ConfNb=1
|
||||
SH.S_TIM2_CH1.0=TIM2_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM2_CH1.ConfNb=1
|
||||
SH.S_TIM3_CH1.0=TIM3_CH1,Input_Capture1_from_TI1
|
||||
SH.S_TIM3_CH1.ConfNb=1
|
||||
SH.S_TIM3_CH2.0=TIM3_CH2,Input_Capture2_from_TI2
|
||||
SH.S_TIM3_CH2.ConfNb=1
|
||||
SH.S_TIM3_CH3.0=TIM3_CH3,Input_Capture3_from_TI3
|
||||
SH.S_TIM3_CH3.ConfNb=1
|
||||
SH.S_TIM3_CH4.0=TIM3_CH4,Input_Capture4_from_TI4
|
||||
SH.S_TIM3_CH4.ConfNb=1
|
||||
SH.S_TIM4_CH1.0=TIM4_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM4_CH1.ConfNb=1
|
||||
SH.S_TIM4_CH2.0=TIM4_CH2,PWM Generation2 CH2
|
||||
SH.S_TIM4_CH2.ConfNb=1
|
||||
SH.S_TIM4_CH3.0=TIM4_CH3,PWM Generation3 CH3
|
||||
SH.S_TIM4_CH3.ConfNb=1
|
||||
SH.S_TIM4_CH4.0=TIM4_CH4,PWM Generation4 CH4
|
||||
SH.S_TIM4_CH4.ConfNb=1
|
||||
SH.S_TIM8_CH1.0=TIM8_CH1
|
||||
SH.S_TIM8_CH1.ConfNb=1
|
||||
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2
|
||||
SPI1.CalculateBaudRate=60.0 MBits/s
|
||||
SPI1.Direction=SPI_DIRECTION_2LINES
|
||||
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler
|
||||
SPI1.Mode=SPI_MODE_MASTER
|
||||
SPI1.VirtualType=VM_MASTER
|
||||
SPI2.CalculateBaudRate=60.0 MBits/s
|
||||
SPI2.Direction=SPI_DIRECTION_2LINES
|
||||
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI2.Mode=SPI_MODE_MASTER
|
||||
SPI2.VirtualType=VM_MASTER
|
||||
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
|
||||
TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
|
||||
TIM1.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
|
||||
TIM1.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4
|
||||
TIM2.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM2.IPParameters=Channel-PWM Generation1 CH1
|
||||
TIM3.Channel-Input_Capture1_from_TI1=TIM_CHANNEL_1
|
||||
TIM3.Channel-Input_Capture2_from_TI2=TIM_CHANNEL_2
|
||||
TIM3.Channel-Input_Capture3_from_TI3=TIM_CHANNEL_3
|
||||
TIM3.Channel-Input_Capture4_from_TI4=TIM_CHANNEL_4
|
||||
TIM3.IPParameters=Channel-Input_Capture1_from_TI1,Channel-Input_Capture3_from_TI3,Channel-Input_Capture4_from_TI4,Channel-Input_Capture2_from_TI2
|
||||
TIM4.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM4.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
|
||||
TIM4.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
|
||||
TIM4.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
|
||||
TIM4.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4
|
||||
USART1.IPParameters=VirtualMode-Asynchronous
|
||||
USART1.VirtualMode-Asynchronous=VM_ASYNC
|
||||
USART2.IPParameters=VirtualMode-Asynchronous
|
||||
USART2.VirtualMode-Asynchronous=VM_ASYNC
|
||||
USART3.IPParameters=VirtualMode-Asynchronous
|
||||
USART3.VirtualMode-Asynchronous=VM_ASYNC
|
||||
VP_SYS_VS_Systick.Mode=SysTick
|
||||
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
||||
board=custom
|
|
@ -0,0 +1,470 @@
|
|||
#MicroXplorer Configuration settings - do not modify
|
||||
ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_15
|
||||
ADC1.IPParameters=Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,OffsetNumber-0\#ChannelRegularConversion,NbrOfConversionFlag,SingleDiff-0\#ChannelRegularConversion,master
|
||||
ADC1.NbrOfConversionFlag=1
|
||||
ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.Rank-0\#ChannelRegularConversion=1
|
||||
ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5
|
||||
ADC1.SingleDiff-0\#ChannelRegularConversion=ADC_DIFFERENTIAL_ENDED
|
||||
ADC1.master=1
|
||||
CAN1.BS1=CAN_BS1_1TQ
|
||||
CAN1.BS2=CAN_BS2_1TQ
|
||||
CAN1.CalculateBaudRate=625000
|
||||
CAN1.CalculateTimeBit=1600
|
||||
CAN1.CalculateTimeQuantum=533.3333333333334
|
||||
CAN1.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,BS1,BS2
|
||||
File.Version=6
|
||||
GPIO.groupedBy=
|
||||
I2C2.IPParameters=Timing
|
||||
I2C2.Timing=0x007074AF
|
||||
KeepUserPlacement=false
|
||||
Mcu.CPN=STM32L4R5VIT6
|
||||
Mcu.Family=STM32L4
|
||||
Mcu.IP0=ADC1
|
||||
Mcu.IP1=CAN1
|
||||
Mcu.IP10=TIM1
|
||||
Mcu.IP11=TIM2
|
||||
Mcu.IP12=TIM3
|
||||
Mcu.IP13=TIM4
|
||||
Mcu.IP14=UART4
|
||||
Mcu.IP15=USART1
|
||||
Mcu.IP16=USART2
|
||||
Mcu.IP17=USART3
|
||||
Mcu.IP18=USB_OTG_FS
|
||||
Mcu.IP2=I2C2
|
||||
Mcu.IP3=LPUART1
|
||||
Mcu.IP4=NVIC
|
||||
Mcu.IP5=RCC
|
||||
Mcu.IP6=SDMMC1
|
||||
Mcu.IP7=SPI1
|
||||
Mcu.IP8=SPI2
|
||||
Mcu.IP9=SYS
|
||||
Mcu.IPNb=19
|
||||
Mcu.Name=STM32L4R5V(G-I)Tx
|
||||
Mcu.Package=LQFP100
|
||||
Mcu.Pin0=PE3
|
||||
Mcu.Pin1=PE4
|
||||
Mcu.Pin10=PA0
|
||||
Mcu.Pin11=PA1
|
||||
Mcu.Pin12=PA2
|
||||
Mcu.Pin13=PA3
|
||||
Mcu.Pin14=PA4
|
||||
Mcu.Pin15=PA5
|
||||
Mcu.Pin16=PA6
|
||||
Mcu.Pin17=PA7
|
||||
Mcu.Pin18=PC4
|
||||
Mcu.Pin19=PC5
|
||||
Mcu.Pin2=PE5
|
||||
Mcu.Pin20=PB0
|
||||
Mcu.Pin21=PB1
|
||||
Mcu.Pin22=PB2
|
||||
Mcu.Pin23=PE7
|
||||
Mcu.Pin24=PE8
|
||||
Mcu.Pin25=PE9
|
||||
Mcu.Pin26=PE10
|
||||
Mcu.Pin27=PE11
|
||||
Mcu.Pin28=PE13
|
||||
Mcu.Pin29=PE14
|
||||
Mcu.Pin3=PE6
|
||||
Mcu.Pin30=PB10
|
||||
Mcu.Pin31=PB11
|
||||
Mcu.Pin32=PB13
|
||||
Mcu.Pin33=PB14
|
||||
Mcu.Pin34=PB15
|
||||
Mcu.Pin35=PD9
|
||||
Mcu.Pin36=PD10
|
||||
Mcu.Pin37=PD12
|
||||
Mcu.Pin38=PD13
|
||||
Mcu.Pin39=PD14
|
||||
Mcu.Pin4=PC13
|
||||
Mcu.Pin40=PD15
|
||||
Mcu.Pin41=PC6
|
||||
Mcu.Pin42=PC7
|
||||
Mcu.Pin43=PC8
|
||||
Mcu.Pin44=PC9
|
||||
Mcu.Pin45=PA9
|
||||
Mcu.Pin46=PA10
|
||||
Mcu.Pin47=PA11
|
||||
Mcu.Pin48=PA12
|
||||
Mcu.Pin49=PA13 (JTMS/SWDIO)
|
||||
Mcu.Pin5=PC14-OSC32_IN (PC14)
|
||||
Mcu.Pin50=PA14 (JTCK/SWCLK)
|
||||
Mcu.Pin51=PA15 (JTDI)
|
||||
Mcu.Pin52=PC10
|
||||
Mcu.Pin53=PC11
|
||||
Mcu.Pin54=PC12
|
||||
Mcu.Pin55=PD0
|
||||
Mcu.Pin56=PD1
|
||||
Mcu.Pin57=PD2
|
||||
Mcu.Pin58=PD3
|
||||
Mcu.Pin59=PD4
|
||||
Mcu.Pin6=PH0-OSC_IN (PH0)
|
||||
Mcu.Pin60=PD5
|
||||
Mcu.Pin61=PD6
|
||||
Mcu.Pin62=PD7
|
||||
Mcu.Pin63=PB3 (JTDO/TRACESWO)
|
||||
Mcu.Pin64=PB4 (NJTRST)
|
||||
Mcu.Pin65=PB5
|
||||
Mcu.Pin66=PB6
|
||||
Mcu.Pin67=PB7
|
||||
Mcu.Pin68=PB8
|
||||
Mcu.Pin69=PB9
|
||||
Mcu.Pin7=PH1-OSC_OUT (PH1)
|
||||
Mcu.Pin70=PE0
|
||||
Mcu.Pin71=VP_SYS_VS_Systick
|
||||
Mcu.Pin8=PC2
|
||||
Mcu.Pin9=PC3
|
||||
Mcu.PinsNb=72
|
||||
Mcu.ThirdPartyNb=0
|
||||
Mcu.UserConstants=
|
||||
Mcu.UserName=STM32L4R5VITx
|
||||
MxCube.Version=6.6.1
|
||||
MxDb.Version=DB.6.0.60
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.ForceEnableDMAVector=true
|
||||
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
|
||||
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
|
||||
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||
PA0.Locked=true
|
||||
PA0.Mode=Asynchronous
|
||||
PA0.Signal=UART4_TX
|
||||
PA1.Locked=true
|
||||
PA1.Mode=Asynchronous
|
||||
PA1.Signal=UART4_RX
|
||||
PA10.Mode=OTG/Dual_Role_Device
|
||||
PA10.Signal=USB_OTG_FS_ID
|
||||
PA11.Locked=true
|
||||
PA11.Mode=OTG/Dual_Role_Device
|
||||
PA11.Signal=USB_OTG_FS_DM
|
||||
PA12.Locked=true
|
||||
PA12.Mode=OTG/Dual_Role_Device
|
||||
PA12.Signal=USB_OTG_FS_DP
|
||||
PA13\ (JTMS/SWDIO).Locked=true
|
||||
PA13\ (JTMS/SWDIO).Signal=SYS_JTMS-SWDIO
|
||||
PA14\ (JTCK/SWCLK).Locked=true
|
||||
PA14\ (JTCK/SWCLK).Signal=SYS_JTCK-SWCLK
|
||||
PA15\ (JTDI).Locked=true
|
||||
PA15\ (JTDI).Signal=S_TIM2_CH1
|
||||
PA2.Locked=true
|
||||
PA2.Mode=Asynchronous
|
||||
PA2.Signal=LPUART1_TX
|
||||
PA3.Locked=true
|
||||
PA3.Mode=Asynchronous
|
||||
PA3.Signal=LPUART1_RX
|
||||
PA4.Locked=true
|
||||
PA4.Signal=GPIO_Output
|
||||
PA5.Locked=true
|
||||
PA5.Mode=Full_Duplex_Master
|
||||
PA5.Signal=SPI1_SCK
|
||||
PA6.Locked=true
|
||||
PA6.Mode=Full_Duplex_Master
|
||||
PA6.Signal=SPI1_MISO
|
||||
PA7.Locked=true
|
||||
PA7.Mode=Full_Duplex_Master
|
||||
PA7.Signal=SPI1_MOSI
|
||||
PA9.Locked=true
|
||||
PA9.Mode=Activate_VBUS
|
||||
PA9.Signal=USB_OTG_FS_VBUS
|
||||
PB0.Locked=true
|
||||
PB0.Signal=ADCx_IN15
|
||||
PB1.Signal=ADCx_IN16
|
||||
PB10.Locked=true
|
||||
PB10.Mode=I2C
|
||||
PB10.Signal=I2C2_SCL
|
||||
PB11.Locked=true
|
||||
PB11.Mode=I2C
|
||||
PB11.Signal=I2C2_SDA
|
||||
PB13.Locked=true
|
||||
PB13.Mode=CTS_RTS
|
||||
PB13.Signal=USART3_CTS
|
||||
PB14.Locked=true
|
||||
PB14.Mode=CTS_RTS
|
||||
PB14.Signal=USART3_RTS
|
||||
PB15.Locked=true
|
||||
PB15.Signal=S_TIM15_CH2
|
||||
PB2.Locked=true
|
||||
PB2.Signal=GPIO_Output
|
||||
PB3\ (JTDO/TRACESWO).Locked=true
|
||||
PB3\ (JTDO/TRACESWO).Mode=CTS_RTS
|
||||
PB3\ (JTDO/TRACESWO).Signal=USART1_RTS
|
||||
PB4\ (NJTRST).Locked=true
|
||||
PB4\ (NJTRST).Mode=CTS_RTS
|
||||
PB4\ (NJTRST).Signal=USART1_CTS
|
||||
PB5.Locked=true
|
||||
PB5.Signal=GPIO_Output
|
||||
PB6.Locked=true
|
||||
PB6.Mode=Asynchronous
|
||||
PB6.Signal=USART1_TX
|
||||
PB7.Locked=true
|
||||
PB7.Mode=Asynchronous
|
||||
PB7.Signal=USART1_RX
|
||||
PB8.Locked=true
|
||||
PB8.Mode=CAN_Activate
|
||||
PB8.Signal=CAN1_RX
|
||||
PB9.Locked=true
|
||||
PB9.Mode=CAN_Activate
|
||||
PB9.Signal=CAN1_TX
|
||||
PC10.Locked=true
|
||||
PC10.Mode=SD_4_bits_Wide_bus
|
||||
PC10.Signal=SDMMC1_D2
|
||||
PC11.Locked=true
|
||||
PC11.Mode=SD_4_bits_Wide_bus
|
||||
PC11.Signal=SDMMC1_D3
|
||||
PC12.Locked=true
|
||||
PC12.Mode=SD_4_bits_Wide_bus
|
||||
PC12.Signal=SDMMC1_CK
|
||||
PC13.Locked=true
|
||||
PC13.Signal=GPIO_Output
|
||||
PC14-OSC32_IN\ (PC14).Locked=true
|
||||
PC14-OSC32_IN\ (PC14).Signal=GPIO_Output
|
||||
PC2.Locked=true
|
||||
PC2.Signal=ADCx_IN3
|
||||
PC3.Locked=true
|
||||
PC3.Signal=ADCx_IN4
|
||||
PC4.Locked=true
|
||||
PC4.Mode=Asynchronous
|
||||
PC4.Signal=USART3_TX
|
||||
PC5.Locked=true
|
||||
PC5.Mode=Asynchronous
|
||||
PC5.Signal=USART3_RX
|
||||
PC6.Locked=true
|
||||
PC6.Signal=S_TIM8_CH1
|
||||
PC7.Locked=true
|
||||
PC7.Signal=GPIO_Output
|
||||
PC8.Locked=true
|
||||
PC8.Mode=SD_4_bits_Wide_bus
|
||||
PC8.Signal=SDMMC1_D0
|
||||
PC9.Locked=true
|
||||
PC9.Mode=SD_4_bits_Wide_bus
|
||||
PC9.Signal=SDMMC1_D1
|
||||
PD0.Locked=true
|
||||
PD0.Signal=GPIO_Output
|
||||
PD1.Locked=true
|
||||
PD1.Mode=Full_Duplex_Master
|
||||
PD1.Signal=SPI2_SCK
|
||||
PD10.Locked=true
|
||||
PD10.Signal=GPIO_Output
|
||||
PD12.Locked=true
|
||||
PD12.Signal=S_TIM4_CH1
|
||||
PD13.Locked=true
|
||||
PD13.Signal=S_TIM4_CH2
|
||||
PD14.Locked=true
|
||||
PD14.Signal=S_TIM4_CH3
|
||||
PD15.Locked=true
|
||||
PD15.Signal=S_TIM4_CH4
|
||||
PD2.Locked=true
|
||||
PD2.Mode=SD_4_bits_Wide_bus
|
||||
PD2.Signal=SDMMC1_CMD
|
||||
PD3.Locked=true
|
||||
PD3.Mode=Full_Duplex_Master
|
||||
PD3.Signal=SPI2_MISO
|
||||
PD4.Locked=true
|
||||
PD4.Mode=Full_Duplex_Master
|
||||
PD4.Signal=SPI2_MOSI
|
||||
PD5.Locked=true
|
||||
PD5.Mode=Asynchronous
|
||||
PD5.Signal=USART2_TX
|
||||
PD6.Locked=true
|
||||
PD6.Mode=Asynchronous
|
||||
PD6.Signal=USART2_RX
|
||||
PD7.Locked=true
|
||||
PD7.Signal=GPIO_Output
|
||||
PD9.Locked=true
|
||||
PD9.Signal=GPIO_Output
|
||||
PE0.Locked=true
|
||||
PE0.Signal=GPIO_Output
|
||||
PE10.Locked=true
|
||||
PE10.Signal=GPIO_Output
|
||||
PE11.Locked=true
|
||||
PE11.Signal=S_TIM1_CH2
|
||||
PE13.Locked=true
|
||||
PE13.Signal=S_TIM1_CH3
|
||||
PE14.Locked=true
|
||||
PE14.Signal=S_TIM1_CH4
|
||||
PE3.Signal=S_TIM3_CH1
|
||||
PE4.Locked=true
|
||||
PE4.Signal=S_TIM3_CH2
|
||||
PE5.Signal=S_TIM3_CH3
|
||||
PE6.Signal=S_TIM3_CH4
|
||||
PE7.Locked=true
|
||||
PE7.Signal=GPIO_Output
|
||||
PE8.Locked=true
|
||||
PE8.Signal=GPIO_Output
|
||||
PE9.Locked=true
|
||||
PE9.Signal=S_TIM1_CH1
|
||||
PH0-OSC_IN\ (PH0).Mode=HSE-External-Oscillator
|
||||
PH0-OSC_IN\ (PH0).Signal=RCC_OSC_IN
|
||||
PH1-OSC_OUT\ (PH1).Mode=HSE-External-Oscillator
|
||||
PH1-OSC_OUT\ (PH1).Signal=RCC_OSC_OUT
|
||||
PinOutPanel.RotationAngle=0
|
||||
ProjectManager.AskForMigrate=true
|
||||
ProjectManager.BackupPrevious=false
|
||||
ProjectManager.CompilerOptimize=6
|
||||
ProjectManager.ComputerToolchain=false
|
||||
ProjectManager.CoupleFile=false
|
||||
ProjectManager.CustomerFirmwarePackage=
|
||||
ProjectManager.DefaultFWLocation=true
|
||||
ProjectManager.DeletePrevious=true
|
||||
ProjectManager.DeviceId=STM32L4R5VITx
|
||||
ProjectManager.FirmwarePackage=STM32Cube FW_L4 V1.17.2
|
||||
ProjectManager.FreePins=false
|
||||
ProjectManager.HalAssertFull=false
|
||||
ProjectManager.HeapSize=0x200
|
||||
ProjectManager.KeepUserCode=true
|
||||
ProjectManager.LastFirmware=true
|
||||
ProjectManager.LibraryCopy=0
|
||||
ProjectManager.MainLocation=Core/Src
|
||||
ProjectManager.NoMain=false
|
||||
ProjectManager.PreviousToolchain=
|
||||
ProjectManager.ProjectBuild=false
|
||||
ProjectManager.ProjectFileName=flamingo_written.ioc
|
||||
ProjectManager.ProjectName=flamingo_written
|
||||
ProjectManager.RegisterCallBack=
|
||||
ProjectManager.StackSize=0x400
|
||||
ProjectManager.TargetToolchain=EWARM
|
||||
ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UnderRoot=false
|
||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN1_Init-CAN1-false-HAL-true,4-MX_TIM3_Init-TIM3-false-HAL-true,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_I2C2_Init-I2C2-false-HAL-true,7-MX_LPUART1_UART_Init-LPUART1-false-HAL-true,8-MX_UART4_Init-UART4-false-HAL-true,9-MX_USART1_UART_Init-USART1-false-HAL-true,10-MX_USART2_UART_Init-USART2-false-HAL-true,11-MX_USART3_UART_Init-USART3-false-HAL-true,12-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,13-MX_SPI1_Init-SPI1-false-HAL-true,14-MX_SPI2_Init-SPI2-false-HAL-true,15-MX_TIM1_Init-TIM1-false-HAL-true,16-MX_TIM2_Init-TIM2-false-HAL-true,17-MX_TIM4_Init-TIM4-false-HAL-true,18-MX_USB_OTG_FS_HCD_Init-USB_OTG_FS-false-HAL-true
|
||||
RCC.ADCFreq_Value=48000000
|
||||
RCC.AHBFreq_Value=32000000
|
||||
RCC.APB1CLKDivider=RCC_HCLK_DIV4
|
||||
RCC.APB1Freq_Value=8000000
|
||||
RCC.APB1TimFreq_Value=16000000
|
||||
RCC.APB2Freq_Value=32000000
|
||||
RCC.APB2TimFreq_Value=32000000
|
||||
RCC.CRSFreq_Value=48000000
|
||||
RCC.CortexFreq_Value=32000000
|
||||
RCC.DFSDMFreq_Value=8000000
|
||||
RCC.FCLKCortexFreq_Value=32000000
|
||||
RCC.FamilyName=M
|
||||
RCC.HCLKFreq_Value=32000000
|
||||
RCC.HSE_VALUE=8000000
|
||||
RCC.HSI48_VALUE=48000000
|
||||
RCC.HSI_VALUE=16000000
|
||||
RCC.I2C1Freq_Value=8000000
|
||||
RCC.I2C2Freq_Value=8000000
|
||||
RCC.I2C3Freq_Value=8000000
|
||||
RCC.I2C4Freq_Value=8000000
|
||||
RCC.IPParameters=ADCFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,DFSDMFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,LCDTFTFreq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSE_VALUE,LSI_VALUE,MCO1PinFreq_Value,MSI_VALUE,OCTOSPIMFreq_Value,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSAI1N,PLLSAI1PoutputFreq_Value,PLLSAI1QoutputFreq_Value,PLLSAI1RoutputFreq_Value,PLLSAI2PoutputFreq_Value,PLLSAI2QoutputFreq_Value,PLLSAI2RoutputFreq_Value,PLLSourceVirtual,PWREXT_OverDrive,PWRFreq_Value,RCC_TIM_PRescaler_Selection,RNGFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMCFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,UART5Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAI1OutputFreq_Value,VCOSAI2OutputFreq_Value
|
||||
RCC.LCDTFTFreq_Value=16000000
|
||||
RCC.LPTIM1Freq_Value=8000000
|
||||
RCC.LPTIM2Freq_Value=8000000
|
||||
RCC.LPUART1Freq_Value=8000000
|
||||
RCC.LSCOPinFreq_Value=32000
|
||||
RCC.LSE_VALUE=32768
|
||||
RCC.LSI_VALUE=32000
|
||||
RCC.MCO1PinFreq_Value=32000000
|
||||
RCC.MSI_VALUE=4000000
|
||||
RCC.OCTOSPIMFreq_Value=32000000
|
||||
RCC.PLLPoutputFreq_Value=32000000
|
||||
RCC.PLLQoutputFreq_Value=32000000
|
||||
RCC.PLLRCLKFreq_Value=32000000
|
||||
RCC.PLLSAI1N=12
|
||||
RCC.PLLSAI1PoutputFreq_Value=48000000
|
||||
RCC.PLLSAI1QoutputFreq_Value=48000000
|
||||
RCC.PLLSAI1RoutputFreq_Value=48000000
|
||||
RCC.PLLSAI2PoutputFreq_Value=32000000
|
||||
RCC.PLLSAI2QoutputFreq_Value=32000000
|
||||
RCC.PLLSAI2RoutputFreq_Value=32000000
|
||||
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
|
||||
RCC.PWREXT_OverDrive=PWREXT_OverDrive_DESACTIVATED
|
||||
RCC.PWRFreq_Value=32000000
|
||||
RCC.RCC_TIM_PRescaler_Selection=RCC_TIMPRES_DESACTIVATED
|
||||
RCC.RNGFreq_Value=48000000
|
||||
RCC.SAI1Freq_Value=48000000
|
||||
RCC.SAI2Freq_Value=48000000
|
||||
RCC.SDMMCFreq_Value=32000000
|
||||
RCC.SYSCLKFreq_VALUE=32000000
|
||||
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
|
||||
RCC.UART4Freq_Value=8000000
|
||||
RCC.UART5Freq_Value=8000000
|
||||
RCC.USART1Freq_Value=32000000
|
||||
RCC.USART2Freq_Value=8000000
|
||||
RCC.USART3Freq_Value=8000000
|
||||
RCC.USBFreq_Value=48000000
|
||||
RCC.VCOInput2Freq_Value=8000000
|
||||
RCC.VCOInput3Freq_Value=8000000
|
||||
RCC.VCOInputFreq_Value=8000000
|
||||
RCC.VCOOutputFreq_Value=64000000
|
||||
RCC.VCOSAI1OutputFreq_Value=96000000
|
||||
RCC.VCOSAI2OutputFreq_Value=64000000
|
||||
SH.ADCx_IN15.0=ADC1_IN15,IN15-Differential
|
||||
SH.ADCx_IN15.ConfNb=1
|
||||
SH.ADCx_IN16.0=ADC1_IN16,IN15-Differential
|
||||
SH.ADCx_IN16.ConfNb=1
|
||||
SH.ADCx_IN3.0=ADC1_IN3
|
||||
SH.ADCx_IN3.ConfNb=1
|
||||
SH.ADCx_IN4.0=ADC1_IN4,IN4-Single-Ended
|
||||
SH.ADCx_IN4.ConfNb=1
|
||||
SH.S_TIM15_CH2.0=TIM15_CH2
|
||||
SH.S_TIM15_CH2.ConfNb=1
|
||||
SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM1_CH1.ConfNb=1
|
||||
SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
|
||||
SH.S_TIM1_CH2.ConfNb=1
|
||||
SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
|
||||
SH.S_TIM1_CH3.ConfNb=1
|
||||
SH.S_TIM1_CH4.0=TIM1_CH4,PWM Generation4 CH4
|
||||
SH.S_TIM1_CH4.ConfNb=1
|
||||
SH.S_TIM2_CH1.0=TIM2_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM2_CH1.ConfNb=1
|
||||
SH.S_TIM3_CH1.0=TIM3_CH1,Input_Capture1_from_TI1
|
||||
SH.S_TIM3_CH1.ConfNb=1
|
||||
SH.S_TIM3_CH2.0=TIM3_CH2,Input_Capture2_from_TI2
|
||||
SH.S_TIM3_CH2.ConfNb=1
|
||||
SH.S_TIM3_CH3.0=TIM3_CH3,Input_Capture3_from_TI3
|
||||
SH.S_TIM3_CH3.ConfNb=1
|
||||
SH.S_TIM3_CH4.0=TIM3_CH4,Input_Capture4_from_TI4
|
||||
SH.S_TIM3_CH4.ConfNb=1
|
||||
SH.S_TIM4_CH1.0=TIM4_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM4_CH1.ConfNb=1
|
||||
SH.S_TIM4_CH2.0=TIM4_CH2,PWM Generation2 CH2
|
||||
SH.S_TIM4_CH2.ConfNb=1
|
||||
SH.S_TIM4_CH3.0=TIM4_CH3,PWM Generation3 CH3
|
||||
SH.S_TIM4_CH3.ConfNb=1
|
||||
SH.S_TIM4_CH4.0=TIM4_CH4,PWM Generation4 CH4
|
||||
SH.S_TIM4_CH4.ConfNb=1
|
||||
SH.S_TIM8_CH1.0=TIM8_CH1
|
||||
SH.S_TIM8_CH1.ConfNb=1
|
||||
SPI1.CalculateBaudRate=16.0 MBits/s
|
||||
SPI1.Direction=SPI_DIRECTION_2LINES
|
||||
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI1.Mode=SPI_MODE_MASTER
|
||||
SPI1.VirtualType=VM_MASTER
|
||||
SPI2.CalculateBaudRate=4.0 MBits/s
|
||||
SPI2.Direction=SPI_DIRECTION_2LINES
|
||||
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI2.Mode=SPI_MODE_MASTER
|
||||
SPI2.VirtualType=VM_MASTER
|
||||
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
|
||||
TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
|
||||
TIM1.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
|
||||
TIM1.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4
|
||||
TIM2.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM2.IPParameters=Channel-PWM Generation1 CH1
|
||||
TIM3.Channel-Input_Capture1_from_TI1=TIM_CHANNEL_1
|
||||
TIM3.Channel-Input_Capture2_from_TI2=TIM_CHANNEL_2
|
||||
TIM3.Channel-Input_Capture3_from_TI3=TIM_CHANNEL_3
|
||||
TIM3.Channel-Input_Capture4_from_TI4=TIM_CHANNEL_4
|
||||
TIM3.IPParameters=Channel-Input_Capture1_from_TI1,Channel-Input_Capture3_from_TI3,Channel-Input_Capture4_from_TI4,Channel-Input_Capture2_from_TI2
|
||||
TIM4.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM4.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
|
||||
TIM4.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
|
||||
TIM4.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
|
||||
TIM4.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4
|
||||
USART1.IPParameters=VirtualMode-Asynchronous
|
||||
USART1.VirtualMode-Asynchronous=VM_ASYNC
|
||||
USART2.IPParameters=VirtualMode-Asynchronous
|
||||
USART2.VirtualMode-Asynchronous=VM_ASYNC
|
||||
USART3.IPParameters=VirtualMode-Asynchronous
|
||||
USART3.VirtualMode-Asynchronous=VM_ASYNC
|
||||
VP_SYS_VS_Systick.Mode=SysTick
|
||||
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
||||
board=custom
|
|
@ -178,7 +178,7 @@ static void stm32_gpio_init(void) {
|
|||
#elif defined(STM32F3)
|
||||
rccResetAHB(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB(STM32_GPIO_EN_MASK, true);
|
||||
#elif defined(STM32G4) || defined(STM32L4)
|
||||
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
rccResetAHB2(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB2(STM32_GPIO_EN_MASK, true);
|
||||
#else
|
||||
|
|
|
@ -505,7 +505,7 @@ static void init_uarts(void)
|
|||
|
||||
/* Baud rate setting.*/
|
||||
uint32_t fck;
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
fck = (uint32_t)(((HAL_CRASH_SERIAL_PORT_CLOCK + ((HAL_CRASH_SERIAL_PORT_BAUD)/2)) / HAL_CRASH_SERIAL_PORT_BAUD));
|
||||
#else
|
||||
#if STM32_HAS_USART6
|
||||
|
@ -516,11 +516,11 @@ static void init_uarts(void)
|
|||
fck = (STM32_PCLK2+((HAL_CRASH_SERIAL_PORT_BAUD)/2)) / HAL_CRASH_SERIAL_PORT_BAUD;
|
||||
else
|
||||
fck = (STM32_PCLK1+((HAL_CRASH_SERIAL_PORT_BAUD)/2)) / HAL_CRASH_SERIAL_PORT_BAUD;
|
||||
#endif //defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#endif //defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
|
||||
u->BRR = fck;
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
/* Resetting eventual pending status flags.*/
|
||||
u->ICR = 0xFFFFFFFFU;
|
||||
#else
|
||||
|
@ -545,7 +545,7 @@ int CrashCatcher_getc(void)
|
|||
static const char* wait_for_string = "dump_crash_log";
|
||||
uint8_t curr_off = 0;
|
||||
while (true) {
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
while (!(USART_ISR_RXNE & u->ISR)) {}
|
||||
uint8_t c = u->RDR;
|
||||
#else
|
||||
|
@ -571,12 +571,12 @@ void CrashCatcher_putc(int c)
|
|||
init_uarts();
|
||||
}
|
||||
USART_TypeDef *u = HAL_CRASH_SERIAL_PORT;
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
u->TDR = c & 0xFF;
|
||||
#else
|
||||
u->DR = c & 0xFF;
|
||||
#endif
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
while (!(USART_ISR_TC & u->ISR)) {
|
||||
#else
|
||||
while (!(USART_SR_TC & u->SR)) {
|
||||
|
|
|
@ -133,6 +133,9 @@ static const uint32_t flash_memmap[STM32_FLASH_NPAGES] = { KB(32), KB(32), KB(32
|
|||
#elif defined(STM32G4)
|
||||
#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2)
|
||||
#define STM32_FLASH_FIXED_PAGE_SIZE 2
|
||||
#elif defined(STM32L4PLUS)
|
||||
#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/4)
|
||||
#define STM32_FLASH_FIXED_PAGE_SIZE 4
|
||||
#elif defined(STM32L4)
|
||||
#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2)
|
||||
#define STM32_FLASH_FIXED_PAGE_SIZE 2
|
||||
|
@ -464,6 +467,15 @@ bool stm32_flash_erasepage(uint32_t page)
|
|||
// there is an 8th bit
|
||||
FLASH->CR |= page<<FLASH_CR_PNB_Pos;
|
||||
FLASH->CR |= FLASH_CR_STRT;
|
||||
#elif defined(STM32L4PLUS)
|
||||
FLASH->CR |= FLASH_CR_PER;
|
||||
if (page >= 256) {
|
||||
FLASH->CR |= FLASH_CR_BKER;
|
||||
}
|
||||
FLASH->CR &= ~FLASH_CR_PNB;
|
||||
|
||||
FLASH->CR |= (page<256 ?page: (page -256))<<FLASH_CR_PNB_Pos;
|
||||
FLASH->CR |= FLASH_CR_STRT;
|
||||
#elif defined(STM32L4)
|
||||
FLASH->CR = FLASH_CR_PER;
|
||||
FLASH->CR |= page<<FLASH_CR_PNB_Pos;
|
||||
|
@ -753,7 +765,7 @@ failed:
|
|||
}
|
||||
#endif // STM32F1 or STM32F3
|
||||
|
||||
#if defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
static bool stm32_flash_write_g4(uint32_t addr, const void *buf, uint32_t count)
|
||||
{
|
||||
uint32_t *b = (uint32_t *)buf;
|
||||
|
@ -838,7 +850,7 @@ bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count)
|
|||
return stm32_flash_write_f4f7(addr, buf, count);
|
||||
#elif defined(STM32H7)
|
||||
return stm32_flash_write_h7(addr, buf, count);
|
||||
#elif defined(STM32G4) || defined(STM32L4)
|
||||
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
return stm32_flash_write_g4(addr, buf, count);
|
||||
#else
|
||||
#error "Unsupported MCU"
|
||||
|
|
|
@ -53,6 +53,8 @@
|
|||
#include "stm32h7_mcuconf.h"
|
||||
#elif defined(STM32G4)
|
||||
#include "stm32g4_mcuconf.h"
|
||||
#elif defined(STM32L4PLUS)
|
||||
#include "stm32l4+_mcuconf.h"
|
||||
#elif defined(STM32L4)
|
||||
#include "stm32l4_mcuconf.h"
|
||||
#else
|
||||
|
|
|
@ -350,7 +350,7 @@ void peripheral_power_enable(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
/*
|
||||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
|
|
|
@ -103,7 +103,7 @@ void malloc_init(void);
|
|||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
*/
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) ||defined(STM32L4PLUS)
|
||||
iomode_t palReadLineMode(ioline_t line);
|
||||
|
||||
enum PalPushPull {
|
||||
|
|
|
@ -0,0 +1,379 @@
|
|||
/*
|
||||
ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
|
||||
|
||||
Licensed under the 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
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
*/
|
||||
#ifndef MCUCONF_H
|
||||
#define MCUCONF_H
|
||||
|
||||
#define STM32L4XX_MCUCONF
|
||||
#define STM32L4R5XX_MCUCONF
|
||||
#define STM32L4R5_MCUCONF
|
||||
|
||||
|
||||
#ifndef STM32_HSI_ENABLED
|
||||
#define STM32_HSI_ENABLED TRUE
|
||||
#endif
|
||||
|
||||
|
||||
#if STM32_HSECLK == 0U
|
||||
// no crystal
|
||||
#define STM32_HSE_ENABLED FALSE
|
||||
#define STM32_HSI16_ENABLED TRUE
|
||||
#define STM32_PLLM_VALUE 2
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSI16
|
||||
|
||||
#elif STM32_HSECLK == 8000000U
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI16_ENABLED FALSE
|
||||
#define STM32_PLLM_VALUE 1
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
|
||||
#elif STM32_HSECLK == 12000000U
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI16_ENABLED FALSE
|
||||
#define STM32_PLLM_VALUE 3
|
||||
#define STM32_PLLN_VALUE 60
|
||||
#define STM32_PLLSAI1N_VALUE 24
|
||||
#define STM32_PLLSAI2N_VALUE 8
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
|
||||
#elif STM32_HSECLK == 16000000U
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI16_ENABLED FALSE
|
||||
#define STM32_PLLM_VALUE 2
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
|
||||
#elif STM32_HSECLK == 24000000U
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI16_ENABLED FALSE
|
||||
#define STM32_PLLM_VALUE 3
|
||||
#define STM32_PLLSAI1M_VALUE 3
|
||||
#define STM32_PLLSAI2M_VALUE 3
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
|
||||
#else
|
||||
#error "Unsupported HSE clock"
|
||||
#endif
|
||||
|
||||
/*
|
||||
* HAL driver system settings.
|
||||
*/
|
||||
#define STM32_NO_INIT FALSE
|
||||
#define STM32_VOS STM32_VOS_RANGE1
|
||||
#define STM32_PVD_ENABLE FALSE
|
||||
#define STM32_PLS STM32_PLS_LEV0
|
||||
#define STM32_HSI48_ENABLED FALSE
|
||||
#define STM32_LSI_ENABLED FALSE
|
||||
#define STM32_LSE_ENABLED FALSE
|
||||
#define STM32_MSIPLL_ENABLED FALSE
|
||||
#define STM32_MSIRANGE STM32_MSIRANGE_4M
|
||||
#define STM32_MSISRANGE STM32_MSISRANGE_4M
|
||||
#define STM32_SW STM32_SW_PLL
|
||||
#ifndef STM32_PLLN_VALUE
|
||||
#define STM32_PLLN_VALUE 30
|
||||
#endif
|
||||
#define STM32_PLLPDIV_VALUE 0
|
||||
#define STM32_PLLP_VALUE 7
|
||||
#define STM32_PLLQ_VALUE 2
|
||||
#define STM32_PLLR_VALUE 2
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV1
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV1
|
||||
#define STM32_STOPWUCK STM32_STOPWUCK_MSI
|
||||
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
|
||||
#define STM32_MCOPRE STM32_MCOPRE_DIV1
|
||||
#define STM32_LSCOSEL STM32_LSCOSEL_NOCLOCK
|
||||
#ifndef STM32_PLLSAI1N_VALUE
|
||||
#define STM32_PLLSAI1N_VALUE 12
|
||||
#endif
|
||||
#define STM32_PLLSAI1PDIV_VALUE 0
|
||||
#define STM32_PLLSAI1P_VALUE 7
|
||||
#define STM32_PLLSAI1Q_VALUE 2
|
||||
#define STM32_PLLSAI1R_VALUE 2
|
||||
#ifndef STM32_PLLSAI2N_VALUE
|
||||
#define STM32_PLLSAI2N_VALUE 8
|
||||
#endif
|
||||
#define STM32_PLLSAI2PDIV_VALUE 0
|
||||
#define STM32_PLLSAI2P_VALUE 7
|
||||
#define STM32_PLLSAI2R_VALUE 2
|
||||
|
||||
#ifndef STM32_LSECLK
|
||||
#define STM32_LSECLK 32768U
|
||||
#endif
|
||||
#ifndef STM32_LSEDRV
|
||||
#define STM32_LSEDRV (3U << 3U)
|
||||
#endif
|
||||
|
||||
#define STM32_VDD 330U
|
||||
|
||||
/*
|
||||
* Peripherals clock sources.
|
||||
*/
|
||||
#define STM32_USART1SEL STM32_USART1SEL_SYSCLK
|
||||
#define STM32_USART2SEL STM32_USART2SEL_SYSCLK
|
||||
#define STM32_USART3SEL STM32_USART3SEL_SYSCLK
|
||||
#define STM32_UART4SEL STM32_UART4SEL_SYSCLK
|
||||
#define STM32_UART5SEL STM32_UART5SEL_SYSCLK
|
||||
#define STM32_LPUART1SEL STM32_LPUART1SEL_SYSCLK
|
||||
#define STM32_I2C1SEL STM32_I2C1SEL_SYSCLK
|
||||
#define STM32_I2C2SEL STM32_I2C2SEL_SYSCLK
|
||||
#define STM32_I2C3SEL STM32_I2C3SEL_SYSCLK
|
||||
#define STM32_I2C4SEL STM32_I2C4SEL_SYSCLK
|
||||
#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1
|
||||
#define STM32_LPTIM2SEL STM32_LPTIM2SEL_PCLK1
|
||||
#define STM32_SAI1SEL STM32_SAI1SEL_OFF
|
||||
#define STM32_SAI2SEL STM32_SAI2SEL_OFF
|
||||
#define STM32_CLK48SEL STM32_CLK48SEL_PLLSAI1
|
||||
#define STM32_ADCSEL STM32_ADCSEL_PLLSAI1
|
||||
#define STM32_DFSDMSEL STM32_DFSDMSEL_PCLK2
|
||||
#define STM32_ADFSDMSEL STM32_ADFSDMSEL_SAI1CLK
|
||||
#define STM32_RTCSEL STM32_RTCSEL_NOCLOCK
|
||||
#define STM32_SDMMCSEL STM32_SDMMCSEL_48CLK
|
||||
#define STM32_DSISEL STM32_DSISEL_DSIPHY
|
||||
|
||||
/*
|
||||
* IRQ system settings.
|
||||
*/
|
||||
#define STM32_IRQ_EXTI0_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI1_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI2_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI3_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI4_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI5_9_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI10_15_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI1635_38_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI18_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI19_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI20_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI21_22_PRIORITY 6
|
||||
|
||||
#define STM32_IRQ_SDMMC1_PRIORITY 9
|
||||
|
||||
#define STM32_IRQ_TIM1_BRK_TIM15_PRIORITY 7
|
||||
#define STM32_IRQ_TIM1_UP_TIM16_PRIORITY 7
|
||||
#define STM32_IRQ_TIM1_TRGCO_TIM17_PRIORITY 7
|
||||
#define STM32_IRQ_TIM1_CC_PRIORITY 7
|
||||
#define STM32_IRQ_TIM2_PRIORITY 7
|
||||
#define STM32_IRQ_TIM3_PRIORITY 7
|
||||
#define STM32_IRQ_TIM4_PRIORITY 7
|
||||
#define STM32_IRQ_TIM5_PRIORITY 7
|
||||
#define STM32_IRQ_TIM6_PRIORITY 7
|
||||
#define STM32_IRQ_TIM7_PRIORITY 7
|
||||
#define STM32_IRQ_TIM8_UP_PRIORITY 7
|
||||
#define STM32_IRQ_TIM8_CC_PRIORITY 7
|
||||
|
||||
#define STM32_IRQ_USART1_PRIORITY 12
|
||||
#define STM32_IRQ_USART2_PRIORITY 12
|
||||
#define STM32_IRQ_USART3_PRIORITY 12
|
||||
#define STM32_IRQ_UART4_PRIORITY 12
|
||||
#define STM32_IRQ_UART5_PRIORITY 12
|
||||
#define STM32_IRQ_LPUART1_PRIORITY 12
|
||||
|
||||
/*
|
||||
* ADC driver system settings.
|
||||
*/
|
||||
#define STM32_ADC_COMPACT_SAMPLES FALSE
|
||||
#define STM32_ADC_USE_ADC1 TRUE
|
||||
#define STM32_ADC_ADC1_DMA_PRIORITY 2
|
||||
#define STM32_ADC_ADC12_IRQ_PRIORITY 5
|
||||
#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 5
|
||||
#define STM32_ADC_ADC123_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV2
|
||||
#define STM32_ADC_ADC123_PRESC ADC_CCR_PRESC_DIV2
|
||||
|
||||
/*
|
||||
* CAN driver system settings.
|
||||
*/
|
||||
#define STM32_CAN_USE_CAN1 FALSE
|
||||
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
|
||||
|
||||
/*
|
||||
* DAC driver system settings.
|
||||
*/
|
||||
#define STM32_DAC_DUAL_MODE FALSE
|
||||
#define STM32_DAC_USE_DAC1_CH1 FALSE
|
||||
#define STM32_DAC_USE_DAC1_CH2 FALSE
|
||||
#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
|
||||
#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
|
||||
#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
|
||||
#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
|
||||
|
||||
/*
|
||||
* DAC driver system settings.
|
||||
*/
|
||||
#define STM32_DAC_DUAL_MODE FALSE
|
||||
#define STM32_DAC_USE_DAC1_CH1 FALSE
|
||||
#define STM32_DAC_USE_DAC1_CH2 FALSE
|
||||
#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
|
||||
#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
|
||||
#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
|
||||
#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
|
||||
#define STM32_DAC_DAC1_CH1_DMA_STREAM STM32_DMA_STREAM_ID_ANY
|
||||
#define STM32_DAC_DAC1_CH2_DMA_STREAM STM32_DMA_STREAM_ID_ANY
|
||||
|
||||
/*
|
||||
* GPT driver system settings.
|
||||
*/
|
||||
#define STM32_GPT_USE_TIM1 FALSE
|
||||
#define STM32_GPT_USE_TIM2 FALSE
|
||||
#define STM32_GPT_USE_TIM3 FALSE
|
||||
#define STM32_GPT_USE_TIM4 FALSE
|
||||
#define STM32_GPT_USE_TIM5 FALSE
|
||||
#define STM32_GPT_USE_TIM6 FALSE
|
||||
#define STM32_GPT_USE_TIM7 FALSE
|
||||
#define STM32_GPT_USE_TIM8 FALSE
|
||||
#define STM32_GPT_USE_TIM15 FALSE
|
||||
#define STM32_GPT_USE_TIM16 FALSE
|
||||
#define STM32_GPT_USE_TIM17 FALSE
|
||||
|
||||
/*
|
||||
* I2C driver system settings.
|
||||
*/
|
||||
#define STM32_I2C_BUSY_TIMEOUT 50
|
||||
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C3_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C4_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C1_DMA_PRIORITY 3
|
||||
#define STM32_I2C_I2C2_DMA_PRIORITY 3
|
||||
#define STM32_I2C_I2C3_DMA_PRIORITY 3
|
||||
#define STM32_I2C_I2C4_DMA_PRIORITY 3
|
||||
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp)
|
||||
|
||||
/*
|
||||
* PWM driver system settings.
|
||||
*/
|
||||
#define STM32_PWM_USE_ADVANCED FALSE
|
||||
|
||||
/*
|
||||
* RTC driver system settings.
|
||||
*/
|
||||
#define STM32_RTC_PRESA_VALUE 32
|
||||
#define STM32_RTC_PRESS_VALUE 1024
|
||||
#define STM32_RTC_CR_INIT 0
|
||||
#define STM32_RTC_TAMPCR_INIT 0
|
||||
|
||||
/*
|
||||
* SDC driver system settings.
|
||||
*/
|
||||
#define STM32_SDC_SDMMC_UNALIGNED_SUPPORT TRUE
|
||||
#define STM32_SDC_SDMMC_WRITE_TIMEOUT 1000000
|
||||
#define STM32_SDC_SDMMC_READ_TIMEOUT 1000000
|
||||
#define STM32_SDC_SDMMC_CLOCK_DELAY 10
|
||||
#define STM32_SDC_SDMMC_PWRSAV TRUE
|
||||
#define STM32_SDC_SDMMC1_IRQ_PRIORITY 9
|
||||
|
||||
/*
|
||||
* SERIAL driver system settings.
|
||||
*/
|
||||
#define STM32_SERIAL_USE_LPUART1 TRUE
|
||||
#define STM32_SERIAL_USART1_PRIORITY 12
|
||||
#define STM32_SERIAL_USART2_PRIORITY 12
|
||||
#define STM32_SERIAL_USART3_PRIORITY 12
|
||||
#define STM32_SERIAL_UART4_PRIORITY 12
|
||||
#define STM32_SERIAL_UART5_PRIORITY 12
|
||||
#define STM32_SERIAL_LPUART1_PRIORITY 12
|
||||
|
||||
/*
|
||||
* SPI driver system settings.
|
||||
*/
|
||||
#define STM32_SPI_SPI1_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI2_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI3_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* ST driver system settings.
|
||||
*/
|
||||
#define STM32_ST_IRQ_PRIORITY 8
|
||||
#ifndef STM32_ST_USE_TIMER
|
||||
#define STM32_ST_USE_TIMER 2
|
||||
#endif
|
||||
|
||||
/*
|
||||
* TRNG driver system settings.
|
||||
*/
|
||||
#define STM32_TRNG_USE_RNG1 FALSE
|
||||
|
||||
|
||||
/*
|
||||
* UART driver system settings.
|
||||
*/
|
||||
#define STM32_UART_USART1_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART2_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART3_IRQ_PRIORITY 12
|
||||
#define STM32_UART_UART4_IRQ_PRIORITY 12
|
||||
#define STM32_UART_UART5_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART1_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART2_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART3_DMA_PRIORITY 0
|
||||
#define STM32_UART_UART4_DMA_PRIORITY 0
|
||||
#define STM32_UART_UART5_DMA_PRIORITY 0
|
||||
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* USB driver system settings.
|
||||
*/
|
||||
#ifndef STM32_USB_USE_OTG1
|
||||
#define STM32_USB_USE_OTG1 FALSE
|
||||
#endif
|
||||
#define STM32_USB_OTG1_IRQ_PRIORITY 14
|
||||
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
|
||||
|
||||
/*
|
||||
* EICU driver system settings.
|
||||
*/
|
||||
#define STM32_EICU_TIM1_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM2_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM3_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM4_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM5_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM8_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM9_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM10_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM11_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM12_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM13_IRQ_PRIORITY 6
|
||||
#define STM32_EICU_TIM15_IRQ_PRIORITY 6
|
||||
|
||||
/*
|
||||
* WDG driver system settings.
|
||||
*/
|
||||
#define STM32_WDG_USE_IWDG FALSE
|
||||
|
||||
/*
|
||||
* WSPI driver system settings.
|
||||
*/
|
||||
#define STM32_WSPI_USE_OCTOSPI1 TRUE
|
||||
#define STM32_WSPI_USE_OCTOSPI2 TRUE
|
||||
#define STM32_WSPI_OCTOSPI1_PRESCALER_VALUE 1
|
||||
#define STM32_WSPI_OCTOSPI2_PRESCALER_VALUE 1
|
||||
#define STM32_WSPI_OCTOSPI1_IRQ_PRIORITY 10
|
||||
#define STM32_WSPI_OCTOSPI2_IRQ_PRIORITY 10
|
||||
#define STM32_WSPI_OCTOSPI1_DMA_STREAM STM32_DMA_STREAM_ID_ANY
|
||||
#define STM32_WSPI_OCTOSPI2_DMA_STREAM STM32_DMA_STREAM_ID_ANY
|
||||
#define STM32_WSPI_OCTOSPI1_DMA_PRIORITY 1
|
||||
#define STM32_WSPI_OCTOSPI2_DMA_PRIORITY 1
|
||||
#define STM32_WSPI_OCTOSPI1_DMA_IRQ_PRIORITY 10
|
||||
#define STM32_WSPI_OCTOSPI2_DMA_IRQ_PRIORITY 10
|
||||
#define STM32_WSPI_DMA_ERROR_HOOK(qspip) osalSysHalt("DMA failure")
|
||||
|
||||
// limit ISR count per byte
|
||||
#define STM32_I2C_ISR_LIMIT 6
|
||||
|
||||
#endif /* MCUCONF_H */
|
||||
|
||||
|
|
@ -40,7 +40,7 @@
|
|||
#define WDG_RESET_CLEAR (1U<<24)
|
||||
#define WDG_RESET_IS_IWDG (1U<<29)
|
||||
#define WDG_RESET_IS_SFT (1U<<28)
|
||||
#elif defined(STM32G4) || defined(STM32L4)
|
||||
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
#define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x94))
|
||||
#define WDG_RESET_CLEAR (1U<<23)
|
||||
#define WDG_RESET_IS_IWDG (1U<<29)
|
||||
|
|
|
@ -0,0 +1,910 @@
|
|||
#!/usr/bin/env python
|
||||
'''
|
||||
these tables are generated from the STM32 datasheet stm32l4R5ai.pdf
|
||||
'''
|
||||
|
||||
# additional build information for ChibiOS
|
||||
build = {
|
||||
"CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32l4xx.mk",
|
||||
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32L4xx+/platform.mk"
|
||||
}
|
||||
|
||||
pincount = {
|
||||
'A': 16,
|
||||
'B': 16,
|
||||
'C': 16,
|
||||
'D': 16,
|
||||
'E': 16,
|
||||
'F': 16,
|
||||
'G': 16,
|
||||
'H': 16,
|
||||
'I': 12,
|
||||
'J': 0,
|
||||
'K': 0
|
||||
}
|
||||
|
||||
|
||||
# MCU parameters
|
||||
mcu = {
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
# we treat SRAM1/SRAM2/SRAM3 as a single region for simplicifty. SRAM2 is parity checked
|
||||
# and is mapped at both 0x20030000 and at 0x10000000
|
||||
(0x20000000, 640, 1), # SRAM1/SRAM2/SRAM3
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 120000000,
|
||||
|
||||
'DEFINES' : {
|
||||
'STM32L4PLUS' : '1',
|
||||
}
|
||||
}
|
||||
|
||||
# no DMA map as we will dynamically allocate DMA channels using the DMAMUX
|
||||
DMA_Map = None
|
||||
|
||||
AltFunction_map = {
|
||||
# format is PIN:FUNCTION : AFNUM
|
||||
"PA0:EVENTOUT" : 15,
|
||||
"PA0:SAI1_EXTCLK" : 13,
|
||||
"PA0:TIM2_CH1" : 1,
|
||||
"PA0:TIM2_ETR" : 14,
|
||||
"PA0:TIM5_CH1" : 2,
|
||||
"PA0:TIM8_ETR" : 3,
|
||||
"PA0:UART4_TX" : 8,
|
||||
"PA0:USART2_CTS" : 7,
|
||||
"PA0:USART2_NSS" : 7,
|
||||
"PA1:EVENTOUT" : 15,
|
||||
"PA1:I2C1_SMBA" : 4,
|
||||
"PA1:OCTOSPIM_P1_DQS" : 10,
|
||||
"PA1:SPI1_SCK" : 5,
|
||||
"PA1:TIM15_CH1N" : 14,
|
||||
"PA1:TIM2_CH2" : 1,
|
||||
"PA1:TIM5_CH2" : 2,
|
||||
"PA1:UART4_RX" : 8,
|
||||
"PA1:USART2_DE" : 7,
|
||||
"PA1:USART2_RTS" : 7,
|
||||
"PA2:EVENTOUT" : 15,
|
||||
"PA2:LPUART1_TX" : 8,
|
||||
"PA2:OCTOSPIM_P1_NCS" : 10,
|
||||
"PA2:SAI2_EXTCLK" : 13,
|
||||
"PA2:TIM15_CH1" : 14,
|
||||
"PA2:TIM2_CH3" : 1,
|
||||
"PA2:TIM5_CH3" : 2,
|
||||
"PA2:USART2_TX" : 7,
|
||||
"PA3:EVENTOUT" : 15,
|
||||
"PA3:LPUART1_RX" : 8,
|
||||
"PA3:OCTOSPIM_P1_CLK" : 10,
|
||||
"PA3:SAI1_CK1" : 3,
|
||||
"PA3:SAI1_MCLK_A" : 13,
|
||||
"PA3:TIM15_CH2" : 14,
|
||||
"PA3:TIM2_CH4" : 1,
|
||||
"PA3:TIM5_CH4" : 2,
|
||||
"PA3:USART2_RX" : 7,
|
||||
"PA4:DCMI_HSYNC" : 10,
|
||||
"PA4:EVENTOUT" : 15,
|
||||
"PA4:LPTIM2_OUT" : 14,
|
||||
"PA4:OCTOSPIM_P1_NCS" : 3,
|
||||
"PA4:SAI1_FS_B" : 13,
|
||||
"PA4:SPI1_NSS" : 5,
|
||||
"PA4:SPI3_NSS" : 6,
|
||||
"PA4:USART2_CK" : 7,
|
||||
"PA5:EVENTOUT" : 15,
|
||||
"PA5:LPTIM2_ETR" : 14,
|
||||
"PA5:SPI1_SCK" : 5,
|
||||
"PA5:TIM2_CH1" : 1,
|
||||
"PA5:TIM2_ETR" : 2,
|
||||
"PA5:TIM8_CH1N" : 3,
|
||||
"PA6:DCMI_PIXCLK" : 4,
|
||||
"PA6:EVENTOUT" : 15,
|
||||
"PA6:LPUART1_CTS" : 8,
|
||||
"PA6:OCTOSPIM_P1_IO3" : 10,
|
||||
"PA6:SPI1_MISO" : 5,
|
||||
"PA6:TIM16_CH1" : 14,
|
||||
"PA6:TIM1_BKIN" : 12,
|
||||
"PA6:TIM3_CH1" : 2,
|
||||
"PA6:TIM8_BKIN" : 13,
|
||||
"PA6:USART3_CTS" : 7,
|
||||
"PA6:USART3_NSS" : 7,
|
||||
"PA7:EVENTOUT" : 15,
|
||||
"PA7:I2C3_SCL" : 4,
|
||||
"PA7:OCTOSPIM_P1_IO2" : 10,
|
||||
"PA7:SPI1_MOSI" : 5,
|
||||
"PA7:TIM17_CH1" : 14,
|
||||
"PA7:TIM1_CH1N" : 1,
|
||||
"PA7:TIM3_CH2" : 2,
|
||||
"PA7:TIM8_CH1N" : 3,
|
||||
"PA8:EVENTOUT" : 15,
|
||||
"PA8:LPTIM2_OUT" : 14,
|
||||
"PA8:RCC_MCO" : 0,
|
||||
"PA8:SAI1_CK2" : 3,
|
||||
"PA8:SAI1_SCK_A" : 13,
|
||||
"PA8:TIM1_CH1" : 1,
|
||||
"PA8:USART1_CK" : 7,
|
||||
"PA8:USB_OTG_FS_SOF" : 10,
|
||||
"PA9:DCMI_D0" : 5,
|
||||
"PA9:EVENTOUT" : 15,
|
||||
"PA9:SAI1_FS_A" : 13,
|
||||
"PA9:SPI2_SCK" : 3,
|
||||
"PA9:TIM15_BKIN" : 14,
|
||||
"PA9:TIM1_CH2" : 1,
|
||||
"PA9:USART1_TX" : 7,
|
||||
"PA10:DCMI_D1" : 5,
|
||||
"PA10:EVENTOUT" : 15,
|
||||
"PA10:SAI1_D1" : 3,
|
||||
"PA10:SAI1_SD_A" : 13,
|
||||
"PA10:TIM17_BKIN" : 14,
|
||||
"PA10:TIM1_CH3" : 1,
|
||||
"PA10:USART1_RX" : 7,
|
||||
"PA10:USB_OTG_FS_ID" : 10,
|
||||
"PA11:CAN1_RX" : 9,
|
||||
"PA11:EVENTOUT" : 15,
|
||||
"PA11:SPI1_MISO" : 5,
|
||||
"PA11:TIM1_BKIN2" : 12,
|
||||
"PA11:TIM1_CH4" : 1,
|
||||
"PA11:USART1_CTS" : 7,
|
||||
"PA11:USART1_NSS" : 7,
|
||||
"PA11:USB_OTG_FS_DM" : 10,
|
||||
"PA12:CAN1_TX" : 9,
|
||||
"PA12:EVENTOUT" : 15,
|
||||
"PA12:SPI1_MOSI" : 5,
|
||||
"PA12:TIM1_ETR" : 1,
|
||||
"PA12:USART1_DE" : 7,
|
||||
"PA12:USART1_RTS" : 7,
|
||||
"PA12:USB_OTG_FS_DP" : 10,
|
||||
"PA13:EVENTOUT" : 15,
|
||||
"PA13:IR_OUT" : 1,
|
||||
"PA13:SAI1_SD_B" : 13,
|
||||
"PA13:JTMS-SWDIO" : 0,
|
||||
"PA13:USB_OTG_FS_NOE" : 10,
|
||||
"PA14:EVENTOUT" : 15,
|
||||
"PA14:I2C1_SMBA" : 4,
|
||||
"PA14:I2C4_SMBA" : 5,
|
||||
"PA14:LPTIM1_OUT" : 1,
|
||||
"PA14:SAI1_FS_B" : 13,
|
||||
"PA14:JTCK-SWCLK" : 0,
|
||||
"PA14:USB_OTG_FS_SOF" : 10,
|
||||
"PA15:EVENTOUT" : 15,
|
||||
"PA15:SAI2_FS_B" : 13,
|
||||
"PA15:SPI1_NSS" : 5,
|
||||
"PA15:SPI3_NSS" : 6,
|
||||
"PA15:JTDI" : 0,
|
||||
"PA15:TIM2_CH1" : 1,
|
||||
"PA15:TIM2_ETR" : 2,
|
||||
"PA15:TSC_G3_IO1" : 9,
|
||||
"PA15:UART4_DE" : 8,
|
||||
"PA15:UART4_RTS" : 8,
|
||||
"PA15:USART2_RX" : 3,
|
||||
"PA15:USART3_DE" : 7,
|
||||
"PA15:USART3_RTS" : 7,
|
||||
"PB0:COMP1_OUT" : 12,
|
||||
"PB0:EVENTOUT" : 15,
|
||||
"PB0:OCTOSPIM_P1_IO1" : 10,
|
||||
"PB0:SAI1_EXTCLK" : 13,
|
||||
"PB0:SPI1_NSS" : 5,
|
||||
"PB0:TIM1_CH2N" : 1,
|
||||
"PB0:TIM3_CH3" : 2,
|
||||
"PB0:TIM8_CH2N" : 3,
|
||||
"PB0:USART3_CK" : 7,
|
||||
"PB1:DFSDM1_DATIN0" : 6,
|
||||
"PB1:EVENTOUT" : 15,
|
||||
"PB1:LPTIM2_IN1" : 14,
|
||||
"PB1:LPUART1_DE" : 8,
|
||||
"PB1:LPUART1_RTS" : 8,
|
||||
"PB1:OCTOSPIM_P1_IO0" : 10,
|
||||
"PB1:TIM1_CH3N" : 1,
|
||||
"PB1:TIM3_CH4" : 2,
|
||||
"PB1:TIM8_CH3N" : 3,
|
||||
"PB1:USART3_DE" : 7,
|
||||
"PB1:USART3_RTS" : 7,
|
||||
"PB2:DFSDM1_CKIN0" : 6,
|
||||
"PB2:EVENTOUT" : 15,
|
||||
"PB2:I2C3_SMBA" : 4,
|
||||
"PB2:LPTIM1_OUT" : 1,
|
||||
"PB2:OCTOSPIM_P1_DQS" : 10,
|
||||
"PB2:RTC_OUT_ALARM" : 0,
|
||||
"PB2:RTC_OUT_CALIB" : 0,
|
||||
"PB3:CRS_SYNC" : 10,
|
||||
"PB3:EVENTOUT" : 15,
|
||||
"PB3:SAI1_SCK_B" : 13,
|
||||
"PB3:SPI1_SCK" : 5,
|
||||
"PB3:SPI3_SCK" : 6,
|
||||
"PB3:JTDO-SWO" : 0,
|
||||
"PB3:TIM2_CH2" : 1,
|
||||
"PB3:USART1_DE" : 7,
|
||||
"PB3:USART1_RTS" : 7,
|
||||
"PB4:DCMI_D12" : 10,
|
||||
"PB4:EVENTOUT" : 15,
|
||||
"PB4:I2C3_SDA" : 4,
|
||||
"PB4:SAI1_MCLK_B" : 13,
|
||||
"PB4:SPI1_MISO" : 5,
|
||||
"PB4:SPI3_MISO" : 6,
|
||||
"PB4:JTRST" : 0,
|
||||
"PB4:TIM17_BKIN" : 14,
|
||||
"PB4:TIM3_CH1" : 2,
|
||||
"PB4:TSC_G2_IO1" : 9,
|
||||
"PB4:UART5_DE" : 8,
|
||||
"PB4:UART5_RTS" : 8,
|
||||
"PB4:USART1_CTS" : 7,
|
||||
"PB4:USART1_NSS" : 7,
|
||||
"PB5:COMP2_OUT" : 12,
|
||||
"PB5:DCMI_D10" : 10,
|
||||
"PB5:EVENTOUT" : 15,
|
||||
"PB5:I2C1_SMBA" : 4,
|
||||
"PB5:LPTIM1_IN1" : 1,
|
||||
"PB5:SAI1_SD_B" : 13,
|
||||
"PB5:SPI1_MOSI" : 5,
|
||||
"PB5:SPI3_MOSI" : 6,
|
||||
"PB5:TIM16_BKIN" : 14,
|
||||
"PB5:TIM3_CH2" : 2,
|
||||
"PB5:TSC_G2_IO2" : 9,
|
||||
"PB5:UART5_CTS" : 8,
|
||||
"PB5:USART1_CK" : 7,
|
||||
"PB6:DCMI_D5" : 10,
|
||||
"PB6:DFSDM1_DATIN5" : 6,
|
||||
"PB6:EVENTOUT" : 15,
|
||||
"PB6:I2C1_SCL" : 4,
|
||||
"PB6:I2C4_SCL" : 5,
|
||||
"PB6:LPTIM1_ETR" : 1,
|
||||
"PB6:SAI1_FS_B" : 13,
|
||||
"PB6:TIM16_CH1N" : 14,
|
||||
"PB6:TIM4_CH1" : 2,
|
||||
"PB6:TIM8_BKIN2" : 12,
|
||||
"PB6:TSC_G2_IO3" : 9,
|
||||
"PB6:USART1_TX" : 7,
|
||||
"PB7:DCMI_VSYNC" : 10,
|
||||
"PB7:DFSDM1_CKIN5" : 6,
|
||||
"PB7:EVENTOUT" : 15,
|
||||
"PB7:FMC_NL" : 12,
|
||||
"PB7:I2C1_SDA" : 4,
|
||||
"PB7:I2C4_SDA" : 5,
|
||||
"PB7:LPTIM1_IN2" : 1,
|
||||
"PB7:TIM17_CH1N" : 14,
|
||||
"PB7:TIM4_CH2" : 2,
|
||||
"PB7:TIM8_BKIN" : 13,
|
||||
"PB7:TSC_G2_IO4" : 9,
|
||||
"PB7:UART4_CTS" : 8,
|
||||
"PB7:USART1_RX" : 7,
|
||||
"PB8:CAN1_RX" : 9,
|
||||
"PB8:DCMI_D6" : 10,
|
||||
"PB8:DFSDM1_CKOUT" : 5,
|
||||
"PB8:DFSDM1_DATIN6" : 6,
|
||||
"PB8:EVENTOUT" : 15,
|
||||
"PB8:I2C1_SCL" : 4,
|
||||
"PB8:SAI1_CK1" : 3,
|
||||
"PB8:SAI1_MCLK_A" : 13,
|
||||
"PB8:SDMMC1_CKIN" : 8,
|
||||
"PB8:SDMMC1_D4" : 12,
|
||||
"PB8:TIM16_CH1" : 14,
|
||||
"PB8:TIM4_CH3" : 2,
|
||||
"PB9:CAN1_TX" : 9,
|
||||
"PB9:DCMI_D7" : 10,
|
||||
"PB9:DFSDM1_CKIN6" : 6,
|
||||
"PB9:EVENTOUT" : 15,
|
||||
"PB9:I2C1_SDA" : 4,
|
||||
"PB9:IR_OUT" : 1,
|
||||
"PB9:SAI1_D2" : 3,
|
||||
"PB9:SAI1_FS_A" : 13,
|
||||
"PB9:SDMMC1_CDIR" : 8,
|
||||
"PB9:SDMMC1_D5" : 12,
|
||||
"PB9:SPI2_NSS" : 5,
|
||||
"PB9:TIM17_CH1" : 14,
|
||||
"PB9:TIM4_CH4" : 2,
|
||||
"PB10:COMP1_OUT" : 12,
|
||||
"PB10:DFSDM1_DATIN7" : 6,
|
||||
"PB10:EVENTOUT" : 15,
|
||||
"PB10:I2C2_SCL" : 4,
|
||||
"PB10:I2C4_SCL" : 3,
|
||||
"PB10:LPUART1_RX" : 8,
|
||||
"PB10:OCTOSPIM_P1_CLK" : 10,
|
||||
"PB10:SAI1_SCK_A" : 13,
|
||||
"PB10:SPI2_SCK" : 5,
|
||||
"PB10:TIM2_CH3" : 1,
|
||||
"PB10:TSC_SYNC" : 9,
|
||||
"PB10:USART3_TX" : 7,
|
||||
"PB11:COMP2_OUT" : 12,
|
||||
"PB11:DFSDM1_CKIN7" : 6,
|
||||
"PB11:EVENTOUT" : 15,
|
||||
"PB11:I2C2_SDA" : 4,
|
||||
"PB11:I2C4_SDA" : 3,
|
||||
"PB11:LPUART1_TX" : 8,
|
||||
"PB11:OCTOSPIM_P1_NCS" : 10,
|
||||
"PB11:TIM2_CH4" : 1,
|
||||
"PB11:USART3_RX" : 7,
|
||||
"PB12:DFSDM1_DATIN1" : 6,
|
||||
"PB12:EVENTOUT" : 15,
|
||||
"PB12:I2C2_SMBA" : 4,
|
||||
"PB12:LPUART1_DE" : 8,
|
||||
"PB12:LPUART1_RTS" : 8,
|
||||
"PB12:SAI2_FS_A" : 13,
|
||||
"PB12:SPI2_NSS" : 5,
|
||||
"PB12:TIM15_BKIN" : 14,
|
||||
"PB12:TIM1_BKIN" : 3,
|
||||
"PB12:TSC_G1_IO1" : 9,
|
||||
"PB12:USART3_CK" : 7,
|
||||
"PB13:DFSDM1_CKIN1" : 6,
|
||||
"PB13:EVENTOUT" : 15,
|
||||
"PB13:I2C2_SCL" : 4,
|
||||
"PB13:LPUART1_CTS" : 8,
|
||||
"PB13:SAI2_SCK_A" : 13,
|
||||
"PB13:SPI2_SCK" : 5,
|
||||
"PB13:TIM15_CH1N" : 14,
|
||||
"PB13:TIM1_CH1N" : 1,
|
||||
"PB13:TSC_G1_IO2" : 9,
|
||||
"PB13:USART3_CTS" : 7,
|
||||
"PB13:USART3_NSS" : 7,
|
||||
"PB14:DFSDM1_DATIN2" : 6,
|
||||
"PB14:EVENTOUT" : 15,
|
||||
"PB14:I2C2_SDA" : 4,
|
||||
"PB14:SAI2_MCLK_A" : 13,
|
||||
"PB14:SPI2_MISO" : 5,
|
||||
"PB14:TIM15_CH1" : 14,
|
||||
"PB14:TIM1_CH2N" : 1,
|
||||
"PB14:TIM8_CH2N" : 3,
|
||||
"PB14:TSC_G1_IO3" : 9,
|
||||
"PB14:USART3_DE" : 7,
|
||||
"PB14:USART3_RTS" : 7,
|
||||
"PB15:DFSDM1_CKIN2" : 6,
|
||||
"PB15:EVENTOUT" : 15,
|
||||
"PB15:RTC_REFIN" : 0,
|
||||
"PB15:SAI2_SD_A" : 13,
|
||||
"PB15:SPI2_MOSI" : 5,
|
||||
"PB15:TIM15_CH2" : 14,
|
||||
"PB15:TIM1_CH3N" : 1,
|
||||
"PB15:TIM8_CH3N" : 3,
|
||||
"PB15:TSC_G1_IO4" : 9,
|
||||
"PC0:DFSDM1_DATIN4" : 6,
|
||||
"PC0:EVENTOUT" : 15,
|
||||
"PC0:I2C3_SCL" : 4,
|
||||
"PC0:LPTIM1_IN1" : 1,
|
||||
"PC0:LPTIM2_IN1" : 14,
|
||||
"PC0:LPUART1_RX" : 8,
|
||||
"PC0:SAI2_FS_A" : 13,
|
||||
"PC1:DFSDM1_CKIN4" : 6,
|
||||
"PC1:EVENTOUT" : 15,
|
||||
"PC1:I2C3_SDA" : 4,
|
||||
"PC1:LPTIM1_OUT" : 1,
|
||||
"PC1:LPUART1_TX" : 8,
|
||||
"PC1:OCTOSPIM_P1_IO4" : 10,
|
||||
"PC1:SAI1_SD_A" : 13,
|
||||
"PC1:SPI2_MOSI" : 3,
|
||||
"PC1:TRACED0" : 0,
|
||||
"PC2:DFSDM1_CKOUT" : 6,
|
||||
"PC2:EVENTOUT" : 15,
|
||||
"PC2:LPTIM1_IN2" : 1,
|
||||
"PC2:OCTOSPIM_P1_IO5" : 10,
|
||||
"PC2:SPI2_MISO" : 5,
|
||||
"PC3:EVENTOUT" : 15,
|
||||
"PC3:LPTIM1_ETR" : 1,
|
||||
"PC3:LPTIM2_ETR" : 14,
|
||||
"PC3:OCTOSPIM_P1_IO6" : 10,
|
||||
"PC3:SAI1_D1" : 3,
|
||||
"PC3:SAI1_SD_A" : 13,
|
||||
"PC3:SPI2_MOSI" : 5,
|
||||
"PC4:EVENTOUT" : 15,
|
||||
"PC4:OCTOSPIM_P1_IO7" : 10,
|
||||
"PC4:USART3_TX" : 7,
|
||||
"PC5:EVENTOUT" : 15,
|
||||
"PC5:SAI1_D3" : 3,
|
||||
"PC5:USART3_RX" : 7,
|
||||
"PC6:DCMI_D0" : 10,
|
||||
"PC6:DFSDM1_CKIN3" : 6,
|
||||
"PC6:EVENTOUT" : 15,
|
||||
"PC6:SAI2_MCLK_A" : 13,
|
||||
"PC6:SDMMC1_D0DIR" : 8,
|
||||
"PC6:SDMMC1_D6" : 12,
|
||||
"PC6:TIM3_CH1" : 2,
|
||||
"PC6:TIM8_CH1" : 3,
|
||||
"PC6:TSC_G4_IO1" : 9,
|
||||
"PC7:DCMI_D1" : 10,
|
||||
"PC7:DFSDM1_DATIN3" : 6,
|
||||
"PC7:EVENTOUT" : 15,
|
||||
"PC7:SAI2_MCLK_B" : 13,
|
||||
"PC7:SDMMC1_D123DIR" : 8,
|
||||
"PC7:SDMMC1_D7" : 12,
|
||||
"PC7:TIM3_CH2" : 2,
|
||||
"PC7:TIM8_CH2" : 3,
|
||||
"PC7:TSC_G4_IO2" : 9,
|
||||
"PC8:DCMI_D2" : 10,
|
||||
"PC8:EVENTOUT" : 15,
|
||||
"PC8:SDMMC1_D0" : 12,
|
||||
"PC8:TIM3_CH3" : 2,
|
||||
"PC8:TIM8_CH3" : 3,
|
||||
"PC8:TSC_G4_IO3" : 9,
|
||||
"PC9:DCMI_D3" : 4,
|
||||
"PC9:EVENTOUT" : 15,
|
||||
"PC9:I2C3_SDA" : 6,
|
||||
"PC9:SAI2_EXTCLK" : 13,
|
||||
"PC9:SDMMC1_D1" : 12,
|
||||
"PC9:TRACED0" : 0,
|
||||
"PC9:TIM3_CH4" : 2,
|
||||
"PC9:TIM8_BKIN2" : 14,
|
||||
"PC9:TIM8_CH4" : 3,
|
||||
"PC9:TSC_G4_IO4" : 9,
|
||||
"PC9:USB_OTG_FS_NOE" : 10,
|
||||
"PC10:DCMI_D8" : 10,
|
||||
"PC10:EVENTOUT" : 15,
|
||||
"PC10:SAI2_SCK_B" : 13,
|
||||
"PC10:SDMMC1_D2" : 12,
|
||||
"PC10:SPI3_SCK" : 6,
|
||||
"PC10:TRACED1" : 0,
|
||||
"PC10:TSC_G3_IO2" : 9,
|
||||
"PC10:UART4_TX" : 8,
|
||||
"PC10:USART3_TX" : 7,
|
||||
"PC11:DCMI_D2" : 4,
|
||||
"PC11:DCMI_D4" : 10,
|
||||
"PC11:EVENTOUT" : 15,
|
||||
"PC11:OCTOSPIM_P1_NCS" : 5,
|
||||
"PC11:SAI2_MCLK_B" : 13,
|
||||
"PC11:SDMMC1_D3" : 12,
|
||||
"PC11:SPI3_MISO" : 6,
|
||||
"PC11:TSC_G3_IO3" : 9,
|
||||
"PC11:UART4_RX" : 8,
|
||||
"PC11:USART3_RX" : 7,
|
||||
"PC12:DCMI_D9" : 10,
|
||||
"PC12:EVENTOUT" : 15,
|
||||
"PC12:SAI2_SD_B" : 13,
|
||||
"PC12:SDMMC1_CK" : 12,
|
||||
"PC12:SPI3_MOSI" : 6,
|
||||
"PC12:TRACED3" : 0,
|
||||
"PC12:TSC_G3_IO4" : 9,
|
||||
"PC12:UART5_TX" : 8,
|
||||
"PC12:USART3_CK" : 7,
|
||||
"PC13:EVENTOUT" : 15,
|
||||
"PC14:EVENTOUT" : 15,
|
||||
"PC15:EVENTOUT" : 15,
|
||||
"PD0:CAN1_RX" : 9,
|
||||
"PD0:DFSDM1_DATIN7" : 6,
|
||||
"PD0:EVENTOUT" : 15,
|
||||
"PD0:FMC_D2" : 12,
|
||||
"PD0:FMC_DA2" : 12,
|
||||
"PD0:SPI2_NSS" : 5,
|
||||
"PD1:CAN1_TX" : 9,
|
||||
"PD1:DFSDM1_CKIN7" : 6,
|
||||
"PD1:EVENTOUT" : 15,
|
||||
"PD1:FMC_D3" : 12,
|
||||
"PD1:FMC_DA3" : 12,
|
||||
"PD1:SPI2_SCK" : 5,
|
||||
"PD2:DCMI_D11" : 10,
|
||||
"PD2:EVENTOUT" : 15,
|
||||
"PD2:SDMMC1_CMD" : 12,
|
||||
"PD2:TRACED2" : 0,
|
||||
"PD2:TIM3_ETR" : 2,
|
||||
"PD2:TSC_SYNC" : 9,
|
||||
"PD2:UART5_RX" : 8,
|
||||
"PD2:USART3_DE" : 7,
|
||||
"PD2:USART3_RTS" : 7,
|
||||
"PD3:DCMI_D5" : 4,
|
||||
"PD3:DFSDM1_DATIN0" : 6,
|
||||
"PD3:EVENTOUT" : 15,
|
||||
"PD3:FMC_CLK" : 12,
|
||||
"PD3:OCTOSPIM_P2_NCS" : 10,
|
||||
"PD3:SPI2_MISO" : 5,
|
||||
"PD3:SPI2_SCK" : 3,
|
||||
"PD3:USART2_CTS" : 7,
|
||||
"PD3:USART2_NSS" : 7,
|
||||
"PD4:DFSDM1_CKIN0" : 6,
|
||||
"PD4:EVENTOUT" : 15,
|
||||
"PD4:FMC_NOE" : 12,
|
||||
"PD4:OCTOSPIM_P1_IO4" : 10,
|
||||
"PD4:SPI2_MOSI" : 5,
|
||||
"PD4:USART2_DE" : 7,
|
||||
"PD4:USART2_RTS" : 7,
|
||||
"PD5:EVENTOUT" : 15,
|
||||
"PD5:FMC_NWE" : 12,
|
||||
"PD5:OCTOSPIM_P1_IO5" : 10,
|
||||
"PD5:USART2_TX" : 7,
|
||||
"PD6:DCMI_D10" : 4,
|
||||
"PD6:DFSDM1_DATIN1" : 6,
|
||||
"PD6:EVENTOUT" : 15,
|
||||
"PD6:FMC_NWAIT" : 12,
|
||||
"PD6:OCTOSPIM_P1_IO6" : 10,
|
||||
"PD6:SAI1_D1" : 3,
|
||||
"PD6:SAI1_SD_A" : 13,
|
||||
"PD6:SPI3_MOSI" : 5,
|
||||
"PD6:USART2_RX" : 7,
|
||||
"PD7:DFSDM1_CKIN1" : 6,
|
||||
"PD7:EVENTOUT" : 15,
|
||||
"PD7:FMC_NCE" : 12,
|
||||
"PD7:FMC_NE1" : 12,
|
||||
"PD7:OCTOSPIM_P1_IO7" : 10,
|
||||
"PD7:USART2_CK" : 7,
|
||||
"PD8:DCMI_HSYNC" : 10,
|
||||
"PD8:EVENTOUT" : 15,
|
||||
"PD8:FMC_D13" : 12,
|
||||
"PD8:FMC_DA13" : 12,
|
||||
"PD8:USART3_TX" : 7,
|
||||
"PD9:DCMI_PIXCLK" : 10,
|
||||
"PD9:EVENTOUT" : 15,
|
||||
"PD9:FMC_D14" : 12,
|
||||
"PD9:FMC_DA14" : 12,
|
||||
"PD9:SAI2_MCLK_A" : 13,
|
||||
"PD9:USART3_RX" : 7,
|
||||
"PD10:EVENTOUT" : 15,
|
||||
"PD10:FMC_D15" : 12,
|
||||
"PD10:FMC_DA15" : 12,
|
||||
"PD10:SAI2_SCK_A" : 13,
|
||||
"PD10:TSC_G6_IO1" : 9,
|
||||
"PD10:USART3_CK" : 7,
|
||||
"PD11:EVENTOUT" : 15,
|
||||
"PD11:FMC_A16" : 12,
|
||||
"PD11:I2C4_SMBA" : 4,
|
||||
"PD11:LPTIM2_ETR" : 14,
|
||||
"PD11:SAI2_SD_A" : 13,
|
||||
"PD11:TSC_G6_IO2" : 9,
|
||||
"PD11:USART3_CTS" : 7,
|
||||
"PD11:USART3_NSS" : 7,
|
||||
"PD12:EVENTOUT" : 15,
|
||||
"PD12:FMC_A17" : 12,
|
||||
"PD12:I2C4_SCL" : 4,
|
||||
"PD12:LPTIM2_IN1" : 14,
|
||||
"PD12:SAI2_FS_A" : 13,
|
||||
"PD12:TIM4_CH1" : 2,
|
||||
"PD12:TSC_G6_IO3" : 9,
|
||||
"PD12:USART3_DE" : 7,
|
||||
"PD12:USART3_RTS" : 7,
|
||||
"PD13:EVENTOUT" : 15,
|
||||
"PD13:FMC_A18" : 12,
|
||||
"PD13:I2C4_SDA" : 4,
|
||||
"PD13:LPTIM2_OUT" : 14,
|
||||
"PD13:TIM4_CH2" : 2,
|
||||
"PD13:TSC_G6_IO4" : 9,
|
||||
"PD14:EVENTOUT" : 15,
|
||||
"PD14:FMC_D0" : 12,
|
||||
"PD14:FMC_DA0" : 12,
|
||||
"PD14:TIM4_CH3" : 2,
|
||||
"PD15:EVENTOUT" : 15,
|
||||
"PD15:FMC_D1" : 12,
|
||||
"PD15:FMC_DA1" : 12,
|
||||
"PD15:TIM4_CH4" : 2,
|
||||
"PE0:DCMI_D2" : 10,
|
||||
"PE0:EVENTOUT" : 15,
|
||||
"PE0:FMC_NBL0" : 12,
|
||||
"PE0:TIM16_CH1" : 14,
|
||||
"PE0:TIM4_ETR" : 2,
|
||||
"PE1:DCMI_D3" : 10,
|
||||
"PE1:EVENTOUT" : 15,
|
||||
"PE1:FMC_NBL1" : 12,
|
||||
"PE1:TIM17_CH1" : 14,
|
||||
"PE2:EVENTOUT" : 15,
|
||||
"PE2:FMC_A23" : 12,
|
||||
"PE2:SAI1_CK1" : 3,
|
||||
"PE2:SAI1_MCLK_A" : 13,
|
||||
"PE2:TRACECLK" : 0,
|
||||
"PE2:TIM3_ETR" : 2,
|
||||
"PE2:TSC_G7_IO1" : 9,
|
||||
"PE3:EVENTOUT" : 15,
|
||||
"PE3:FMC_A19" : 12,
|
||||
"PE3:OCTOSPIM_P1_DQS" : 3,
|
||||
"PE3:SAI1_SD_B" : 13,
|
||||
"PE3:TRACED0" : 0,
|
||||
"PE3:TIM3_CH1" : 2,
|
||||
"PE3:TSC_G7_IO2" : 9,
|
||||
"PE4:DCMI_D4" : 10,
|
||||
"PE4:DFSDM1_DATIN3" : 6,
|
||||
"PE4:EVENTOUT" : 15,
|
||||
"PE4:FMC_A20" : 12,
|
||||
"PE4:SAI1_D2" : 3,
|
||||
"PE4:SAI1_FS_A" : 13,
|
||||
"PE4:TRACED1" : 0,
|
||||
"PE4:TIM3_CH2" : 2,
|
||||
"PE4:TSC_G7_IO3" : 9,
|
||||
"PE5:DCMI_D6" : 10,
|
||||
"PE5:DFSDM1_CKIN3" : 6,
|
||||
"PE5:EVENTOUT" : 15,
|
||||
"PE5:FMC_A21" : 12,
|
||||
"PE5:SAI1_CK2" : 3,
|
||||
"PE5:SAI1_SCK_A" : 13,
|
||||
"PE5:TRACED2" : 0,
|
||||
"PE5:TIM3_CH3" : 2,
|
||||
"PE5:TSC_G7_IO4" : 9,
|
||||
"PE6:DCMI_D7" : 10,
|
||||
"PE6:EVENTOUT" : 15,
|
||||
"PE6:FMC_A22" : 12,
|
||||
"PE6:SAI1_D1" : 3,
|
||||
"PE6:SAI1_SD_A" : 13,
|
||||
"PE6:TRACED3" : 0,
|
||||
"PE6:TIM3_CH4" : 2,
|
||||
"PE7:DFSDM1_DATIN2" : 6,
|
||||
"PE7:EVENTOUT" : 15,
|
||||
"PE7:FMC_D4" : 12,
|
||||
"PE7:FMC_DA4" : 12,
|
||||
"PE7:SAI1_SD_B" : 13,
|
||||
"PE7:TIM1_ETR" : 1,
|
||||
"PE8:DFSDM1_CKIN2" : 6,
|
||||
"PE8:EVENTOUT" : 15,
|
||||
"PE8:FMC_D5" : 12,
|
||||
"PE8:FMC_DA5" : 12,
|
||||
"PE8:SAI1_SCK_B" : 13,
|
||||
"PE8:TIM1_CH1N" : 1,
|
||||
"PE9:DFSDM1_CKOUT" : 6,
|
||||
"PE9:EVENTOUT" : 15,
|
||||
"PE9:FMC_D6" : 12,
|
||||
"PE9:FMC_DA6" : 12,
|
||||
"PE9:SAI1_FS_B" : 13,
|
||||
"PE9:TIM1_CH1" : 1,
|
||||
"PE10:DFSDM1_DATIN4" : 6,
|
||||
"PE10:EVENTOUT" : 15,
|
||||
"PE10:FMC_D7" : 12,
|
||||
"PE10:FMC_DA7" : 12,
|
||||
"PE10:OCTOSPIM_P1_CLK" : 10,
|
||||
"PE10:SAI1_MCLK_B" : 13,
|
||||
"PE10:TIM1_CH2N" : 1,
|
||||
"PE10:TSC_G5_IO1" : 9,
|
||||
"PE11:DFSDM1_CKIN4" : 6,
|
||||
"PE11:EVENTOUT" : 15,
|
||||
"PE11:FMC_D8" : 12,
|
||||
"PE11:FMC_DA8" : 12,
|
||||
"PE11:OCTOSPIM_P1_NCS" : 10,
|
||||
"PE11:TIM1_CH2" : 1,
|
||||
"PE11:TSC_G5_IO2" : 9,
|
||||
"PE12:DFSDM1_DATIN5" : 6,
|
||||
"PE12:EVENTOUT" : 15,
|
||||
"PE12:FMC_D9" : 12,
|
||||
"PE12:FMC_DA9" : 12,
|
||||
"PE12:OCTOSPIM_P1_IO0" : 10,
|
||||
"PE12:SPI1_NSS" : 5,
|
||||
"PE12:TIM1_CH3N" : 1,
|
||||
"PE12:TSC_G5_IO3" : 9,
|
||||
"PE13:DFSDM1_CKIN5" : 6,
|
||||
"PE13:EVENTOUT" : 15,
|
||||
"PE13:FMC_D10" : 12,
|
||||
"PE13:FMC_DA10" : 12,
|
||||
"PE13:OCTOSPIM_P1_IO1" : 10,
|
||||
"PE13:SPI1_SCK" : 5,
|
||||
"PE13:TIM1_CH3" : 1,
|
||||
"PE13:TSC_G5_IO4" : 9,
|
||||
"PE14:EVENTOUT" : 15,
|
||||
"PE14:FMC_D11" : 12,
|
||||
"PE14:FMC_DA11" : 12,
|
||||
"PE14:OCTOSPIM_P1_IO2" : 10,
|
||||
"PE14:SPI1_MISO" : 5,
|
||||
"PE14:TIM1_BKIN2" : 3,
|
||||
"PE14:TIM1_CH4" : 1,
|
||||
"PE15:EVENTOUT" : 15,
|
||||
"PE15:FMC_D12" : 12,
|
||||
"PE15:FMC_DA12" : 12,
|
||||
"PE15:OCTOSPIM_P1_IO3" : 10,
|
||||
"PE15:SPI1_MOSI" : 5,
|
||||
"PE15:TIM1_BKIN" : 3,
|
||||
"PF0:EVENTOUT" : 15,
|
||||
"PF0:FMC_A0" : 12,
|
||||
"PF0:I2C2_SDA" : 4,
|
||||
"PF0:OCTOSPIM_P2_IO0" : 5,
|
||||
"PF1:EVENTOUT" : 15,
|
||||
"PF1:FMC_A1" : 12,
|
||||
"PF1:I2C2_SCL" : 4,
|
||||
"PF1:OCTOSPIM_P2_IO1" : 5,
|
||||
"PF2:EVENTOUT" : 15,
|
||||
"PF2:FMC_A2" : 12,
|
||||
"PF2:I2C2_SMBA" : 4,
|
||||
"PF2:OCTOSPIM_P2_IO2" : 5,
|
||||
"PF3:EVENTOUT" : 15,
|
||||
"PF3:FMC_A3" : 12,
|
||||
"PF3:OCTOSPIM_P2_IO3" : 5,
|
||||
"PF4:EVENTOUT" : 15,
|
||||
"PF4:FMC_A4" : 12,
|
||||
"PF4:OCTOSPIM_P2_CLK" : 5,
|
||||
"PF5:EVENTOUT" : 15,
|
||||
"PF5:FMC_A5" : 12,
|
||||
"PF10:DCMI_D11" : 10,
|
||||
"PF10:DFSDM1_CKOUT" : 6,
|
||||
"PF10:EVENTOUT" : 15,
|
||||
"PF10:OCTOSPIM_P1_CLK" : 3,
|
||||
"PF10:SAI1_D3" : 13,
|
||||
"PF10:TIM15_CH2" : 14,
|
||||
"PF11:DCMI_D12" : 10,
|
||||
"PF11:EVENTOUT" : 15,
|
||||
"PF12:EVENTOUT" : 15,
|
||||
"PF12:FMC_A6" : 12,
|
||||
"PF12:OCTOSPIM_P2_DQS" : 5,
|
||||
"PF13:DFSDM1_DATIN6" : 6,
|
||||
"PF13:EVENTOUT" : 15,
|
||||
"PF13:FMC_A7" : 12,
|
||||
"PF13:I2C4_SMBA" : 4,
|
||||
"PF14:DFSDM1_CKIN6" : 6,
|
||||
"PF14:EVENTOUT" : 15,
|
||||
"PF14:FMC_A8" : 12,
|
||||
"PF14:I2C4_SCL" : 4,
|
||||
"PF14:TSC_G8_IO1" : 9,
|
||||
"PF15:EVENTOUT" : 15,
|
||||
"PF15:FMC_A9" : 12,
|
||||
"PF15:I2C4_SDA" : 4,
|
||||
"PF15:TSC_G8_IO2" : 9,
|
||||
"PG0:EVENTOUT" : 15,
|
||||
"PG0:FMC_A10" : 12,
|
||||
"PG0:OCTOSPIM_P2_IO4" : 5,
|
||||
"PG0:TSC_G8_IO3" : 9,
|
||||
"PG1:EVENTOUT" : 15,
|
||||
"PG1:FMC_A11" : 12,
|
||||
"PG1:OCTOSPIM_P2_IO5" : 5,
|
||||
"PG1:TSC_G8_IO4" : 9,
|
||||
"PG2:EVENTOUT" : 15,
|
||||
"PG2:FMC_A12" : 12,
|
||||
"PG2:SAI2_SCK_B" : 13,
|
||||
"PG2:SPI1_SCK" : 5,
|
||||
"PG3:EVENTOUT" : 15,
|
||||
"PG3:FMC_A13" : 12,
|
||||
"PG3:SAI2_FS_B" : 13,
|
||||
"PG3:SPI1_MISO" : 5,
|
||||
"PG4:EVENTOUT" : 15,
|
||||
"PG4:FMC_A14" : 12,
|
||||
"PG4:SAI2_MCLK_B" : 13,
|
||||
"PG4:SPI1_MOSI" : 5,
|
||||
"PG5:EVENTOUT" : 15,
|
||||
"PG5:FMC_A15" : 12,
|
||||
"PG5:LPUART1_CTS" : 8,
|
||||
"PG5:SAI2_SD_B" : 13,
|
||||
"PG5:SPI1_NSS" : 5,
|
||||
"PG6:EVENTOUT" : 15,
|
||||
"PG6:I2C3_SMBA" : 4,
|
||||
"PG6:LPUART1_DE" : 8,
|
||||
"PG6:LPUART1_RTS" : 8,
|
||||
"PG6:OCTOSPIM_P1_DQS" : 3,
|
||||
"PG7:DFSDM1_CKOUT" : 6,
|
||||
"PG7:EVENTOUT" : 15,
|
||||
"PG7:FMC_INT" : 12,
|
||||
"PG7:I2C3_SCL" : 4,
|
||||
"PG7:LPUART1_TX" : 8,
|
||||
"PG7:OCTOSPIM_P2_DQS" : 5,
|
||||
"PG7:SAI1_CK1" : 3,
|
||||
"PG7:SAI1_MCLK_A" : 13,
|
||||
"PG8:EVENTOUT" : 15,
|
||||
"PG8:I2C3_SDA" : 4,
|
||||
"PG8:LPUART1_RX" : 8,
|
||||
"PG9:EVENTOUT" : 15,
|
||||
"PG9:FMC_NCE" : 12,
|
||||
"PG9:FMC_NE2" : 12,
|
||||
"PG9:OCTOSPIM_P2_IO6" : 5,
|
||||
"PG9:SAI2_SCK_A" : 13,
|
||||
"PG9:SPI3_SCK" : 6,
|
||||
"PG9:TIM15_CH1N" : 14,
|
||||
"PG9:USART1_TX" : 7,
|
||||
"PG10:EVENTOUT" : 15,
|
||||
"PG10:FMC_NE3" : 12,
|
||||
"PG10:LPTIM1_IN1" : 1,
|
||||
"PG10:OCTOSPIM_P2_IO7" : 5,
|
||||
"PG10:SAI2_FS_A" : 13,
|
||||
"PG10:SPI3_MISO" : 6,
|
||||
"PG10:TIM15_CH1" : 14,
|
||||
"PG10:USART1_RX" : 7,
|
||||
"PG11:EVENTOUT" : 15,
|
||||
"PG11:LPTIM1_IN2" : 1,
|
||||
"PG11:OCTOSPIM_P1_IO5" : 3,
|
||||
"PG11:SAI2_MCLK_A" : 13,
|
||||
"PG11:SPI3_MOSI" : 6,
|
||||
"PG11:TIM15_CH2" : 14,
|
||||
"PG11:USART1_CTS" : 7,
|
||||
"PG11:USART1_NSS" : 7,
|
||||
"PG12:EVENTOUT" : 15,
|
||||
"PG12:FMC_NE4" : 12,
|
||||
"PG12:LPTIM1_ETR" : 1,
|
||||
"PG12:OCTOSPIM_P2_NCS" : 5,
|
||||
"PG12:SAI2_SD_A" : 13,
|
||||
"PG12:SPI3_NSS" : 6,
|
||||
"PG12:USART1_DE" : 7,
|
||||
"PG12:USART1_RTS" : 7,
|
||||
"PG13:EVENTOUT" : 15,
|
||||
"PG13:FMC_A24" : 12,
|
||||
"PG13:I2C1_SDA" : 4,
|
||||
"PG13:USART1_CK" : 7,
|
||||
"PG14:EVENTOUT" : 15,
|
||||
"PG14:FMC_A25" : 12,
|
||||
"PG14:I2C1_SCL" : 4,
|
||||
"PG15:DCMI_D13" : 10,
|
||||
"PG15:EVENTOUT" : 15,
|
||||
"PG15:I2C1_SMBA" : 4,
|
||||
"PG15:LPTIM1_OUT" : 1,
|
||||
"PG15:OCTOSPIM_P2_DQS" : 5,
|
||||
"PH0:EVENTOUT" : 15,
|
||||
"PH1:EVENTOUT" : 15,
|
||||
"PH2:EVENTOUT" : 15,
|
||||
"PH2:OCTOSPIM_P1_IO4" : 3,
|
||||
"PH3:EVENTOUT" : 15,
|
||||
"PH4:EVENTOUT" : 15,
|
||||
"PH4:I2C2_SCL" : 4,
|
||||
"PH4:OCTOSPIM_P2_DQS" : 5,
|
||||
"PH5:DCMI_PIXCLK" : 10,
|
||||
"PH5:EVENTOUT" : 15,
|
||||
"PH5:I2C2_SDA" : 4,
|
||||
"PH6:DCMI_D8" : 10,
|
||||
"PH6:EVENTOUT" : 15,
|
||||
"PH6:I2C2_SMBA" : 4,
|
||||
"PH6:OCTOSPIM_P2_CLK" : 5,
|
||||
"PH7:DCMI_D9" : 10,
|
||||
"PH7:EVENTOUT" : 15,
|
||||
"PH7:I2C3_SCL" : 4,
|
||||
"PH8:DCMI_HSYNC" : 10,
|
||||
"PH8:EVENTOUT" : 15,
|
||||
"PH8:I2C3_SDA" : 4,
|
||||
"PH8:OCTOSPIM_P2_IO3" : 5,
|
||||
"PH9:DCMI_D0" : 10,
|
||||
"PH9:EVENTOUT" : 15,
|
||||
"PH9:I2C3_SMBA" : 4,
|
||||
"PH9:OCTOSPIM_P2_IO4" : 5,
|
||||
"PH10:DCMI_D1" : 10,
|
||||
"PH10:EVENTOUT" : 15,
|
||||
"PH10:OCTOSPIM_P2_IO5" : 5,
|
||||
"PH10:TIM5_CH1" : 2,
|
||||
"PH11:DCMI_D2" : 10,
|
||||
"PH11:EVENTOUT" : 15,
|
||||
"PH11:OCTOSPIM_P2_IO6" : 5,
|
||||
"PH11:TIM5_CH2" : 2,
|
||||
"PH12:DCMI_D3" : 10,
|
||||
"PH12:EVENTOUT" : 15,
|
||||
"PH12:OCTOSPIM_P2_IO7" : 5,
|
||||
"PH12:TIM5_CH3" : 2,
|
||||
"PH13:CAN1_TX" : 9,
|
||||
"PH13:EVENTOUT" : 15,
|
||||
"PH13:TIM8_CH1N" : 3,
|
||||
"PH14:DCMI_D4" : 10,
|
||||
"PH14:EVENTOUT" : 15,
|
||||
"PH14:TIM8_CH2N" : 3,
|
||||
"PH15:DCMI_D11" : 10,
|
||||
"PH15:EVENTOUT" : 15,
|
||||
"PH15:OCTOSPIM_P2_IO6" : 5,
|
||||
"PH15:TIM8_CH3N" : 3,
|
||||
"PI0:DCMI_D13" : 10,
|
||||
"PI0:EVENTOUT" : 15,
|
||||
"PI0:OCTOSPIM_P1_IO5" : 3,
|
||||
"PI0:SPI2_NSS" : 5,
|
||||
"PI0:TIM5_CH4" : 2,
|
||||
"PI1:DCMI_D8" : 10,
|
||||
"PI1:EVENTOUT" : 15,
|
||||
"PI1:SPI2_SCK" : 5,
|
||||
"PI2:DCMI_D9" : 10,
|
||||
"PI2:EVENTOUT" : 15,
|
||||
"PI2:SPI2_MISO" : 5,
|
||||
"PI2:TIM8_CH4" : 3,
|
||||
"PI3:DCMI_D10" : 10,
|
||||
"PI3:EVENTOUT" : 15,
|
||||
"PI3:SPI2_MOSI" : 5,
|
||||
"PI3:TIM8_ETR" : 3,
|
||||
"PI4:DCMI_D5" : 10,
|
||||
"PI4:EVENTOUT" : 15,
|
||||
"PI4:TIM8_BKIN" : 3,
|
||||
"PI5:DCMI_VSYNC" : 10,
|
||||
"PI5:EVENTOUT" : 15,
|
||||
"PI5:OCTOSPIM_P2_NCS" : 5,
|
||||
"PI5:TIM8_CH1" : 3,
|
||||
"PI6:DCMI_D6" : 10,
|
||||
"PI6:EVENTOUT" : 15,
|
||||
"PI6:OCTOSPIM_P2_CLK" : 5,
|
||||
"PI6:TIM8_CH2" : 3,
|
||||
"PI7:DCMI_D7" : 10,
|
||||
"PI7:EVENTOUT" : 15,
|
||||
"PI7:TIM8_CH3" : 3,
|
||||
"PI8:DCMI_D12" : 10,
|
||||
"PI8:EVENTOUT" : 15,
|
||||
"PI8:OCTOSPIM_P2_NCS" : 5,
|
||||
"PI9:CAN1_RX" : 9,
|
||||
"PI9:EVENTOUT" : 15,
|
||||
"PI9:OCTOSPIM_P2_IO2" : 5,
|
||||
"PI10:EVENTOUT" : 15,
|
||||
"PI10:OCTOSPIM_P2_IO1" : 5,
|
||||
"PI11:EVENTOUT" : 15,
|
||||
"PI11:OCTOSPIM_P2_IO0" : 5,
|
||||
}
|
||||
|
||||
ADC1_map = {
|
||||
# format is PIN : ADC1_CHAN
|
||||
"PA0" : 5,
|
||||
"PA1" : 6,
|
||||
"PA2" : 7,
|
||||
"PA3" : 8,
|
||||
"PA4" : 9,
|
||||
"PA5" : 10,
|
||||
"PA6" : 11,
|
||||
"PA7" : 12,
|
||||
"PC4" : 13,
|
||||
"PC5" : 14,
|
||||
"PB0" : 15,
|
||||
"PB1" : 16,
|
||||
"PC0" : 1,
|
||||
"PC1" : 2,
|
||||
"PC2" : 3,
|
||||
"PC3" : 4,
|
||||
}
|
||||
|
|
@ -764,9 +764,19 @@ def get_flash_pages_sizes():
|
|||
return [ 1 ] * get_config('FLASH_SIZE_KB', type=int)
|
||||
elif (mcu_series.startswith('STM32F105') or
|
||||
mcu_series.startswith('STM32F3') or
|
||||
mcu_series.startswith('STM32G4') or
|
||||
mcu_series.startswith('STM32L4')):
|
||||
mcu_series.startswith('STM32G4')):
|
||||
return [ 2 ] * (get_config('FLASH_SIZE_KB', type=int)//2)
|
||||
elif mcu_series.startswith('STM32L4'):
|
||||
defines = get_mcu_config('DEFINES', False)
|
||||
if defines is not None:
|
||||
if 'STM32L4PLUS' in defines.keys():
|
||||
# STM32L4PLUS
|
||||
return [ 4 ] * (get_config('FLASH_SIZE_KB', type=int)//4)
|
||||
else:
|
||||
# STM32L4
|
||||
return [ 2 ] * (get_config('FLASH_SIZE_KB', type=int)//2)
|
||||
else:
|
||||
return [ 2 ] * (get_config('FLASH_SIZE_KB', type=int)//2)
|
||||
else:
|
||||
raise Exception("Unsupported flash size MCU %s" % mcu_series)
|
||||
|
||||
|
|
Loading…
Reference in New Issue