From bc1de7a2089ee24e1a818e7dc2001681addecb6f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 31 Oct 2019 21:59:23 +1100 Subject: [PATCH] HAL_ChibiOS: support STM32F3xx MCUs --- libraries/AP_HAL_ChibiOS/I2CDevice.cpp | 6 +- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 6 +- libraries/AP_HAL_ChibiOS/hwdef/common/board.c | 5 +- libraries/AP_HAL_ChibiOS/hwdef/common/flash.c | 11 +- .../AP_HAL_ChibiOS/hwdef/common/mcuconf.h | 2 + .../hwdef/common/stm32f3_mcuconf.h | 165 +++++++ .../AP_HAL_ChibiOS/hwdef/common/watchdog.c | 4 +- .../hwdef/scripts/STM32F303xC.py | 462 ++++++++++++++++++ .../AP_HAL_ChibiOS/hwdef/scripts/af_parse.py | 4 +- .../hwdef/scripts/chibios_hwdef.py | 2 +- 10 files changed, 653 insertions(+), 14 deletions(-) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index 01c5e38f40..59bd1decc6 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -123,7 +123,7 @@ I2CDeviceManager::I2CDeviceManager(void) drop the speed to be the minimum speed requested */ businfo[i].busclock = HAL_I2C_MAX_CLOCK; -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) if (businfo[i].busclock <= 100000) { businfo[i].i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR; businfo[i].busclock = 100000; @@ -155,7 +155,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) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) if (bus_clock <= 100000) { bus.i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR; bus.busclock = 100000; @@ -202,7 +202,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, return false; } -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) if (_use_smbus) { bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN; } else { diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 0c0d460148..95182c1f94 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -257,7 +257,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) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR); #else dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR); @@ -355,7 +355,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx) (void *)this); osalDbgAssert(txdma, "stream alloc failed"); chSysUnlock(); -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR); #else dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR); @@ -397,6 +397,7 @@ void UARTDriver::tx_complete(void* self, uint32_t flags) } +#ifndef HAL_UART_NODMA void UARTDriver::rx_irq_cb(void* self) { #if HAL_USE_SERIAL == TRUE @@ -418,6 +419,7 @@ void UARTDriver::rx_irq_cb(void* self) #endif // STM32F7 #endif // HAL_USE_SERIAL } +#endif void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c index 227dad2e15..44824d232a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c @@ -47,7 +47,7 @@ const PALConfig pal_default_config = {VAL_GPIOE_ODR, VAL_GPIOE_CRL, VAL_GPIOE_CRH}, }; -#else //Other than STM32F1 series +#else //Other than STM32F1/F3 series /** * @brief Type of STM32 GPIO port setup. @@ -173,6 +173,9 @@ static void stm32_gpio_init(void) { #if defined(STM32H7) rccResetAHB4(STM32_GPIO_EN_MASK); rccEnableAHB4(STM32_GPIO_EN_MASK, true); +#elif defined(STM32F3) + rccResetAHB(STM32_GPIO_EN_MASK); + rccEnableAHB(STM32_GPIO_EN_MASK, true); #else rccResetAHB1(STM32_GPIO_EN_MASK); rccEnableAHB1(STM32_GPIO_EN_MASK, true); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 9595e5fafe..4c5e4d4915 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -118,6 +118,9 @@ static const uint32_t flash_memmap[STM32_FLASH_NPAGES] = { KB(32), KB(32), KB(32 #elif defined(STM32F105_MCUCONF) #define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2) #define STM32_FLASH_FIXED_PAGE_SIZE 2 +#elif defined(STM32F303_MCUCONF) +#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2) +#define STM32_FLASH_FIXED_PAGE_SIZE 2 #else #error "Unsupported processor for flash.c" #endif @@ -366,7 +369,7 @@ bool stm32_flash_erasepage(uint32_t page) FLASH->CR2 |= FLASH_CR_START; while (FLASH->SR2 & FLASH_SR_QW) ; } -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) FLASH->CR = FLASH_CR_PER; FLASH->AR = stm32_flash_getpageaddr(page); FLASH->CR |= FLASH_CR_STRT; @@ -556,7 +559,7 @@ uint32_t _flash_fail_addr; uint32_t _flash_fail_count; uint8_t *_flash_fail_buf; -#if defined(STM32F1) +#if defined(STM32F1) || defined(STM32F3) static bool stm32_flash_write_f1(uint32_t addr, const void *buf, uint32_t count) { uint8_t *b = (uint8_t *)buf; @@ -616,11 +619,11 @@ failed: #endif return false; } -#endif // STM32F1 +#endif // STM32F1 or STM32F3 bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count) { -#if defined(STM32F1) +#if defined(STM32F1) || defined(STM32F3) return stm32_flash_write_f1(addr, buf, count); #elif defined(STM32F4) || defined(STM32F7) return stm32_flash_write_f4f7(addr, buf, count); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h index 1ffd5d8982..8900caa486 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h @@ -39,6 +39,8 @@ #if defined(STM32F1) #include "stm32f1_mcuconf.h" +#elif defined(STM32F3) +#include "stm32f3_mcuconf.h" #elif defined(STM32F4) || defined(STM32F7) #include "stm32f47_mcuconf.h" #elif defined(STM32H7) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h new file mode 100644 index 0000000000..4aa233f15e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h @@ -0,0 +1,165 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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. +*/ + +#pragma once +/* + * STM32F303 drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the whole + * driver is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +#define STM32F3xx_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_HSI_ENABLED TRUE +#define STM32_LSI_ENABLED FALSE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE + +#if STM32_HSECLK == 8000000U +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 +#define STM32_PLLMUL_VALUE 9 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_HPRE STM32_HPRE_DIV1 +#else +#error "Unsupported STM32F1xx clock frequency" +#endif + +#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK +#define STM32_RTCSEL STM32_RTCSEL_HSEDIV +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC1_IRQ_PRIORITY 6 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 + +/* + * GPT driver system settings. + */ +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 + +/* + * 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_I2C1_DMA_PRIORITY 3 +#define STM32_I2C_I2C2_DMA_PRIORITY 3 +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") + +/* + * ICU driver system settings. + */ +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 + +/* + * RTC driver system settings. + */ +#define STM32_RTC_IRQ_PRIORITY 15 + +/* + * SERIAL driver system settings. + */ +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 + +/* + * SPI driver system settings. + */ +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_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 +/* + * 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_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") + +/* + * WDG driver system settings. + */ +#define STM32_WDG_USE_IWDG FALSE + +#ifndef STM32_ADC_USE_ADC1 +#define STM32_ADC_USE_ADC1 FALSE +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c index b73d5bb5a4..a450643d20 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c @@ -11,7 +11,7 @@ #define IWDG_BASE 0x58004800 #elif defined(STM32F7) || defined(STM32F4) #define IWDG_BASE 0x40003000 -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) #define IWDG_BASE 0x40003000 #else #error "Unsupported IWDG MCU config" @@ -33,7 +33,7 @@ #define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x74)) #define WDG_RESET_CLEAR (1U<<24) #define WDG_RESET_IS_IWDG (1U<<29) -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) #define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x24)) #define WDG_RESET_CLEAR (1U<<24) #define WDG_RESET_IS_IWDG (1U<<29) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py new file mode 100644 index 0000000000..fd19eb8ba7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py @@ -0,0 +1,462 @@ +#!/usr/bin/env python +''' +these tables are generated from the STM32 datasheets for the +STM32F303 +''' + +# additional build information for ChibiOS +build = { + "CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f3xx.mk", + "CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F3xx/platform.mk" + } + +# MCU parameters +mcu = { + # location of MCU serial number + 'UDID_START' : 0x1FFFF7AC, + + # 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' : [ + (0x20000000, 40, 1), # main memory, DMA safe + (0x10000000, 8, 2), # CCM memory, faster, but not DMA safe + ] +} + +AltFunction_map = { + # format is PIN:FUNCTION : AFNUM + # extracted from tabula-AF-STM32F303cc.csv + "PA0:COMP1_OUT" : 8, + "PA0:EVENTOUT" : 15, + "PA0:TIM2_CH1_ETR" : 1, + "PA0:TIM8_BKIN" : 9, + "PA0:TIM8_ETR" : 10, + "PA0:TSC_G1_IO1" : 3, + "PA0:USART2_CTS" : 7, + "PA1:EVENTOUT" : 15, + "PA1:RTC_REFIN" : 0, + "PA1:TIM15_CH1N" : 9, + "PA1:TIM2_CH2" : 1, + "PA1:TSC_G1_IO2" : 3, + "PA1:USART2_RTS_DE" : 7, + "PA2:COMP2_OUT" : 8, + "PA2:EVENTOUT" : 15, + "PA2:TIM15_CH1" : 9, + "PA2:TIM2_CH3" : 1, + "PA2:TSC_G1_IO3" : 3, + "PA2:USART2_TX" : 7, + "PA3:EVENTOUT" : 15, + "PA3:TIM15_CH2" : 9, + "PA3:TIM2_CH4" : 1, + "PA3:TSC_G1_IO4" : 3, + "PA3:USART2_RX" : 7, + "PA4:EVENTOUT" : 15, + "PA4:SPI1_NSS" : 5, + "PA4:SPI3_NSS,I2S3_WS" : 6, + "PA4:TIM3_CH2" : 2, + "PA4:TSC_G2_IO1" : 3, + "PA4:USART2_CK" : 7, + "PA5:EVENTOUT" : 15, + "PA5:SPI1_SCK" : 5, + "PA5:TIM2_CH1_ETR" : 1, + "PA5:TSC_G2_IO2" : 3, + "PA6:COMP1_OUT" : 8, + "PA6:EVENTOUT" : 15, + "PA6:SPI1_MISO" : 5, + "PA6:TIM16_CH1" : 1, + "PA6:TIM1_BKIN" : 6, + "PA6:TIM3_CH1" : 2, + "PA6:TIM8_BKIN" : 4, + "PA6:TSC_G2_IO3" : 3, + "PA7:COMP2_OUT" : 8, + "PA7:EVENTOUT" : 15, + "PA7:SPI1_MOSI" : 5, + "PA7:TIM17_CH1" : 1, + "PA7:TIM1_CH1N" : 6, + "PA7:TIM3_CH2" : 2, + "PA7:TIM8_CH1N" : 4, + "PA7:TSC_G2_IO4" : 3, + "PA8:COMP3_OUT" : 8, + "PA8:EVENTOUT" : 15, + "PA8:I2C2_SMBA" : 4, + "PA8:I2S2_MCK" : 5, + "PA8:MCO" : 0, + "PA8:TIM1_CH1" : 6, + "PA8:TIM4_ETR" : 10, + "PA8:USART1_CK" : 7, + "PA9:COMP5_OUT" : 8, + "PA9:EVENTOUT" : 15, + "PA9:I2C2_SCL" : 4, + "PA9:I2S3_MCK" : 5, + "PA9:TIM15_BKIN" : 9, + "PA9:TIM1_CH2" : 6, + "PA9:TIM2_CH3" : 10, + "PA9:TSC_G4_IO1" : 3, + "PA9:USART1_TX" : 7, + "PA10:COMP6_OUT" : 8, + "PA10:EVENTOUT" : 15, + "PA10:I2C2_SDA" : 4, + "PA10:TIM17_BKIN" : 1, + "PA10:TIM1_CH3" : 6, + "PA10:TIM2_CH4" : 10, + "PA10:TIM8_BKIN" : 11, + "PA10:TSC_G4_IO2" : 3, + "PA10:USART1_RX" : 7, + "PA11:CAN_RX" : 9, + "PA11:COMP1_OUT" : 8, + "PA11:EVENTOUT" : 15, + "PA11:TIM1_BKIN2" : 12, + "PA11:TIM1_CH1N" : 6, + "PA11:TIM1_CH4" : 11, + "PA11:TIM4_CH1" : 10, + "PA11:USART1_CTS" : 7, + "PA11:USB_DM" : 14, + "PA12:CAN_TX" : 9, + "PA12:COMP2_OUT" : 8, + "PA12:EVENTOUT" : 15, + "PA12:TIM16_CH1" : 1, + "PA12:TIM1_CH2N" : 6, + "PA12:TIM1_ETR" : 11, + "PA12:TIM4_CH2" : 10, + "PA12:USART1_RTS_DE" : 7, + "PA12:USB_DP" : 14, + "PA13:EVENTOUT" : 15, + "PA13:IR_OUT" : 5, + "PA13:SWDIO-JTMS" : 0, + "PA13:TIM16_CH1N" : 1, + "PA13:TIM4_CH3" : 10, + "PA13:TSC_G4_IO3" : 3, + "PA13:USART3_CTS" : 7, + "PA14:EVENTOUT" : 15, + "PA14:I2C1_SDA" : 4, + "PA14:SWCLK-JTCK" : 0, + "PA14:TIM1_BKIN" : 6, + "PA14:TIM8_CH2" : 5, + "PA14:TSC_G4_IO4" : 3, + "PA14:USART2_TX" : 7, + "PA15:EVENTOUT" : 15, + "PA15:I2C1_SCL" : 4, + "PA15:JTDI" : 0, + "PA15:SPI1_NSS" : 5, + "PA15:SPI3_NSS,I2S3_WS" : 6, + "PA15:TIM1_BKIN" : 9, + "PA15:TIM2_CH1_ETR" : 1, + "PA15:TIM8_CH1" : 2, + "PA15:USART2_RX" : 7, + "PB0:EVENTOUT" : 12, + "PB0:TIM1_CH2N" : 6, + "PB0:TIM3_CH3" : 2, + "PB0:TIM8_CH2N" : 4, + "PB0:TSC_G3_IO2" : 3, + "PB1:COMP4_OUT" : 8, + "PB1:EVENTOUT" : 12, + "PB1:TIM1_CH3N" : 6, + "PB1:TIM3_CH4" : 2, + "PB1:TIM8_CH3N" : 4, + "PB1:TSC_G3_IO3" : 3, + "PB2:EVENTOUT" : 12, + "PB2:TSC_G3_IO4" : 3, + "PB3:EVENTOUT" : 12, + "PB3:JTDO-TRACESWO" : 0, + "PB3:SPI1_SCK" : 5, + "PB3:SPI3_SCK,I2S3_CK" : 6, + "PB3:TIM2_CH2" : 1, + "PB3:TIM3_ETR" : 10, + "PB3:TIM4_ETR" : 2, + "PB3:TIM8_CH1N" : 4, + "PB3:TSC_G5_IO1" : 3, + "PB3:USART2_TX" : 7, + "PB4:EVENTOUT" : 12, + "PB4:NJTRST" : 0, + "PB4:SPI1_MISO" : 5, + "PB4:SPI3_MISO,I2S3EXT_SD" : 6, + "PB4:TIM16_CH1" : 1, + "PB4:TIM17_BKIN" : 10, + "PB4:TIM3_CH1" : 2, + "PB4:TIM8_CH2N" : 4, + "PB4:TSC_G5_IO2" : 3, + "PB4:USART2_RX" : 7, + "PB5:EVENTOUT" : 12, + "PB5:I2C1_SMBA" : 4, + "PB5:SPI1_MOSI" : 5, + "PB5:SPI3_MOSI,I2S3_SD" : 6, + "PB5:TIM16_BKIN" : 1, + "PB5:TIM17_CH1" : 10, + "PB5:TIM3_CH2" : 2, + "PB5:TIM8_CH3N" : 3, + "PB5:USART2_CK" : 7, + "PB6:EVENTOUT" : 12, + "PB6:I2C1_SCL" : 4, + "PB6:TIM16_CH1N" : 1, + "PB6:TIM4_CH1" : 2, + "PB6:TIM8_BKIN2" : 10, + "PB6:TIM8_CH1" : 5, + "PB6:TIM8_ETR" : 6, + "PB6:TSC_G5_IO3" : 3, + "PB6:USART1_TX" : 7, + "PB7:EVENTOUT" : 12, + "PB7:I2C1_SDA" : 4, + "PB7:TIM17_CH1N" : 1, + "PB7:TIM3_CH4" : 10, + "PB7:TIM4_CH2" : 2, + "PB7:TIM8_BKIN" : 5, + "PB7:TSC_G5_IO4" : 3, + "PB7:USART1_RX" : 7, + "PB8:CAN_RX" : 9, + "PB8:COMP1_OUT" : 8, + "PB8:EVENTOUT" : 12, + "PB8:I2C1_SCL" : 4, + "PB8:TIM16_CH1" : 1, + "PB8:TIM1_BKIN" : 11, + "PB8:TIM4_CH3" : 2, + "PB8:TIM8_CH2" : 10, + "PB8:TSC_SYNC" : 3, + "PB9:CAN_TX" : 9, + "PB9:COMP2_OUT" : 8, + "PB9:EVENTOUT" : 12, + "PB9:I2C1_SDA" : 4, + "PB9:IR_OUT" : 6, + "PB9:TIM17_CH1" : 1, + "PB9:TIM4_CH4" : 2, + "PB9:TIM8_CH3" : 10, + "PB10:EVENTOUT" : 12, + "PB10:TIM2_CH3" : 1, + "PB10:TSC_SYNC" : 3, + "PB10:USART3_TX" : 7, + "PB11:EVENTOUT" : 12, + "PB11:TIM2_CH4" : 1, + "PB11:TSC_G6_IO1" : 3, + "PB11:USART3_RX" : 7, + "PB12:EVENTOUT" : 12, + "PB12:I2C2_SMBA" : 4, + "PB12:SPI2_NSS,I2S2_WS" : 5, + "PB12:TIM1_BKIN" : 6, + "PB12:TSC_G6_IO2" : 3, + "PB12:USART3_CK" : 7, + "PB13:EVENTOUT" : 12, + "PB13:SPI2_SCK,I2S2_CK" : 5, + "PB13:TIM1_CH1N" : 6, + "PB13:TSC_G6_IO3" : 3, + "PB13:USART3_CTS" : 7, + "PB14:EVENTOUT" : 12, + "PB14:SPI2_MISO,I2S2EXT_SD" : 5, + "PB14:TIM15_CH1" : 1, + "PB14:TIM1_CH2N" : 6, + "PB14:TSC_G6_IO4" : 3, + "PB14:USART3_RTS_DE" : 7, + "PB15:EVENTOUT" : 12, + "PB15:RTC_REFIN" : 0, + "PB15:SPI2_MOSI,I2S2_SD" : 5, + "PB15:TIM15_CH1N" : 2, + "PB15:TIM15_CH2" : 1, + "PB15:TIM1_CH3N" : 4, + "PC0:EVENTOUT" : 0, + "PC1:EVENTOUT" : 0, + "PC2:COMP7_OUT" : 2, + "PC2:EVENTOUT" : 0, + "PC3:EVENTOUT" : 0, + "PC3:TIM1_BKIN2" : 5, + "PC4:EVENTOUT" : 0, + "PC4:USART1_TX" : 6, + "PC5:EVENTOUT" : 0, + "PC5:TSC_G3_IO1" : 2, + "PC5:USART1_RX" : 6, + "PC6:COMP6_OUT" : 6, + "PC6:EVENTOUT" : 0, + "PC6:I2S2_MCK" : 5, + "PC6:TIM3_CH1" : 1, + "PC6:TIM8_CH1" : 3, + "PC7:COMP5_OUT" : 6, + "PC7:EVENTOUT" : 0, + "PC7:I2S3_MCK" : 5, + "PC7:TIM3_CH2" : 1, + "PC7:TIM8_CH2" : 3, + "PC8:COMP3_OUT" : 6, + "PC8:EVENTOUT" : 0, + "PC8:TIM3_CH3" : 1, + "PC8:TIM8_CH3" : 3, + "PC9:EVENTOUT" : 0, + "PC9:I2S_CKIN" : 4, + "PC9:TIM3_CH4" : 1, + "PC9:TIM8_BKIN2" : 5, + "PC9:TIM8_CH4" : 3, + "PC10:EVENTOUT" : 0, + "PC10:SPI3_SCK,I2S3_CK" : 5, + "PC10:TIM8_CH1N" : 3, + "PC10:UART4_TX" : 4, + "PC10:USART3_TX" : 6, + "PC11:EVENTOUT" : 0, + "PC11:SPI3_MISO,I2S3EXT_SD" : 5, + "PC11:TIM8_CH2N" : 3, + "PC11:UART4_RX" : 4, + "PC11:USART3_RX" : 6, + "PC12:EVENTOUT" : 0, + "PC12:SPI3_MOSI,I2S3_SD" : 5, + "PC12:TIM8_CH3N" : 3, + "PC12:UART5_TX" : 4, + "PC12:USART3_CK" : 6, + "PC13:TIM1_CH1N" : 3, + "PD0:CAN_RX" : 6, + "PD0:EVENTOUT" : 0, + "PD1:CAN_TX" : 6, + "PD1:EVENTOUT" : 0, + "PD1:TIM8_BKIN2" : 5, + "PD1:TIM8_CH4" : 3, + "PD2:EVENTOUT" : 0, + "PD2:TIM3_ETR" : 1, + "PD2:TIM8_BKIN" : 3, + "PD2:UART5_RX" : 4, + "PD3:EVENTOUT" : 0, + "PD3:TIM2_CH1_ETR" : 1, + "PD3:USART2_CTS" : 6, + "PD4:EVENTOUT" : 0, + "PD4:TIM2_CH2" : 1, + "PD4:USART2_RTS_DE" : 6, + "PD5:EVENTOUT" : 0, + "PD5:USART2_TX" : 6, + "PD6:EVENTOUT" : 0, + "PD6:TIM2_CH4" : 1, + "PD6:USART2_RX" : 6, + "PD7:EVENTOUT" : 0, + "PD7:TIM2_CH3" : 1, + "PD7:USART2_CK" : 6, + "PD8:EVENTOUT" : 0, + "PD8:USART3_TX" : 6, + "PD9:EVENTOUT" : 0, + "PD9:USART3_RX" : 6, + "PD10:EVENTOUT" : 0, + "PD10:USART3_CK" : 6, + "PD11:EVENTOUT" : 0, + "PD11:USART3_CTS" : 6, + "PD12:EVENTOUT" : 0, + "PD12:TIM4_CH1" : 1, + "PD12:TSC_G8_IO1" : 2, + "PD12:USART3_RTS_DE" : 6, + "PD13:EVENTOUT" : 0, + "PD13:TIM4_CH2" : 1, + "PD13:TSC_G8_IO2" : 2, + "PD14:EVENTOUT" : 0, + "PD14:TIM4_CH3" : 1, + "PD14:TSC_G8_IO3" : 2, + "PD15:EVENTOUT" : 0, + "PD15:SPI2_NSS" : 5, + "PD15:TIM4_CH4" : 1, + "PD15:TSC_G8_IO4" : 2, + "PE0:EVENTOUT" : 1, + "PE0:TIM16_CH1" : 4, + "PE0:TIM4_ETR" : 2, + "PE0:USART1_TX" : 6, + "PE1:EVENTOUT" : 1, + "PE1:TIM17_CH1" : 4, + "PE1:USART1_RX" : 6, + "PE2:EVENTOUT" : 1, + "PE2:TIM3_CH1" : 2, + "PE2:TRACECK" : 0, + "PE2:TSC_G7_IO1" : 3, + "PE3:EVENTOUT" : 1, + "PE3:TIM3_CH2" : 2, + "PE3:TRACED0" : 0, + "PE3:TSC_G7_IO2" : 3, + "PE4:EVENTOUT" : 1, + "PE4:TIM3_CH3" : 2, + "PE4:TRACED1" : 0, + "PE4:TSC_G7_IO3" : 3, + "PE5:EVENTOUT" : 1, + "PE5:TIM3_CH4" : 2, + "PE5:TRACED2" : 0, + "PE5:TSC_G7_IO4" : 3, + "PE6:EVENTOUT" : 1, + "PE6:TRACED3" : 0, + "PE7:EVENTOUT" : 1, + "PE7:TIM1_ETR" : 2, + "PE8:EVENTOUT" : 1, + "PE8:TIM1_CH1N" : 2, + "PE9:EVENTOUT" : 1, + "PE9:TIM1_CH1" : 2, + "PE10:EVENTOUT" : 1, + "PE10:TIM1_CH2N" : 2, + "PE11:EVENTOUT" : 1, + "PE11:TIM1_CH2" : 2, + "PE12:EVENTOUT" : 1, + "PE12:TIM1_CH3N" : 2, + "PE13:EVENTOUT" : 1, + "PE13:TIM1_CH3" : 2, + "PE14:EVENTOUT" : 1, + "PE14:TIM1_BKIN2" : 5, + "PE14:TIM1_CH4" : 2, + "PE15:EVENTOUT" : 1, + "PE15:TIM1_BKIN" : 2, + "PE15:USART3_RX" : 6, + "PF0:I2C2_SDA" : 3, + "PF0:TIM1_CH3N" : 5, + "PF1:I2C2_SCL" : 3, + "PF2:EVENTOUT" : 0, + "PF4:COMP1_OUT" : 1, + "PF4:EVENTOUT" : 0, + "PF6:EVENTOUT" : 0, + "PF6:I2C2_SCL" : 3, + "PF6:TIM4_CH4" : 1, + "PF6:USART3_RTS_DE" : 6, + "PF9:EVENTOUT" : 0, + "PF9:SPI2_SCK" : 4, + "PF9:TIM15_CH1" : 2, + "PF10:EVENTOUT" : 0, + "PF10:SPI2_SCK" : 4, + "PF10:TIM15_CH2" : 2, +} + +ADC1_map = { + # format is PIN : ADC1_CHAN + # extracted from tabula-addfunc-F405.csv + "PA0" : 1, + "PA1" : 2, + "PA2" : 3, + "PA3" : 4, + "PF4" : 5, + "PC0" : 6, + "PC1" : 7, + "PC2" : 8, + "PC3" : 9, + "PF2" : 10, +} + +DMA_Map = { + # format is (DMA_TABLE, StreamNum, Channel) + # extracted from tabula-STM32F303-DMA.csv + "ADC1" : [(1,1,0)], + "SPI1_RX" : [(1,2,0)], + "SPI1_TX" : [(1,3,0)], + "SPI2_RX" : [(1,4,0)], + "SPI2_TX" : [(1,5,0)], + "USART3_TX" : [(1,2,0)], + "USART3_RX" : [(1,3,0)], + "USART1_TX" : [(1,4,0)], + "USART1_RX" : [(1,5,0)], + "USART2_TX" : [(1,6,0)], + "USART2_RX" : [(1,7,0)], + "I2C2_TX" : [(1,4,0)], + "I2C2_RX" : [(1,5,0)], + "I2C1_TX" : [(1,6,0)], + "I2C1_RX" : [(1,7,0)], + "TIM1_CH1" : [(1,2,0)], + "TIM1_CH2" : [(1,3,0)], + "TIM1_CH4" : [(1,4,0)], + "TIM1_UP" : [(1,5,0)], + "TIM1_CH3" : [(1,6,0)], + "TIM2_CH3" : [(1,1,0)], + "TIM2_UP" : [(1,2,0)], + "TIM2_CH1" : [(1,5,0)], + "TIM2_CH2" : [(1,7,0)], + "TIM2_CH4" : [(1,7,0)], + "TIM3_CH3" : [(1,2,0)], + "TIM3_CH4" : [(1,3,0)], + "TIM3_UP" : [(1,3,0)], + "TIM3_CH1" : [(1,6,0)], + "TIM15_CH1" : [(1,5,0)], + "TIM15_UP" : [(1,5,0)], + "TIM16_CH1" : [(1,3,0)], + "TIM16_UP" : [(1,3,0)], + "TIM17_CH1" : [(1,1,0)], + "TIM17_UP" : [(1,1,0)], +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py index 2b0ace05ed..b65f7141b7 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py @@ -47,7 +47,7 @@ def pin_compare(p1, p2): return 1 def parse_af_table(fname, table): - csvt = csv.reader(open(fname,'rb')) + csvt = csv.reader(open(fname,'r')) i = 0 aflist = [] for row in csvt: @@ -63,6 +63,8 @@ def parse_af_table(fname, table): row = row[1:] pin = row[0] for i in range(len(aflist)): + if len(row) <= i+1: + break af = aflist[i] s = row[i+1] s = s.replace('_\r', '_') diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 82341c87be..c7f31ae82c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -999,7 +999,7 @@ def write_UART_config(f): f.write( "#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, false, " % (dev, n)) - if mcu_series.startswith("STM32F1"): + if mcu_series.startswith("STM32F1") or mcu_series.startswith("STM32F3"): f.write("%s, " % rts_line) else: f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, " %