diff --git a/boards/stm32f030f4-demo/Makefile b/boards/stm32f030f4-demo/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/stm32f030f4-demo/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/stm32f030f4-demo/Makefile.features b/boards/stm32f030f4-demo/Makefile.features new file mode 100644 index 0000000000..06f731e30a --- /dev/null +++ b/boards/stm32f030f4-demo/Makefile.features @@ -0,0 +1,10 @@ +CPU = stm32f0 +CPU_MODEL = stm32f030f4 + +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_adc +FEATURES_PROVIDED += periph_pwm +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart +FEATURES_PROVIDED += periph_spi +FEATURES_PROVIDED += periph_rtc diff --git a/boards/stm32f030f4-demo/Makefile.include b/boards/stm32f030f4-demo/Makefile.include new file mode 100644 index 0000000000..aa3f38dfad --- /dev/null +++ b/boards/stm32f030f4-demo/Makefile.include @@ -0,0 +1,18 @@ +INCLUDES += -I$(RIOTBOARD)/common/stm32/include + +# configure the serial terminal +PORT_LINUX ?= /dev/ttyACM0 +PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*))) + +# setup serial terminal +include $(RIOTMAKE)/tools/serial.inc.mk + +# stm32 boards can become un-flashable after a hardfault, +# use connect_assert_srst to always be able to flash or reset the boards. +export OPENOCD_RESET_USE_CONNECT_ASSERT_SRST ?= 1 + +# all Nucleo boards have an on-board ST-link adapter +DEBUG_ADAPTER ?= stlink + +# stlink use openocd +include $(RIOTMAKE)/tools/openocd.inc.mk diff --git a/boards/stm32f030f4-demo/board.c b/boards/stm32f030f4-demo/board.c new file mode 100644 index 0000000000..b5f9a9ff08 --- /dev/null +++ b/boards/stm32f030f4-demo/board.c @@ -0,0 +1,30 @@ +/* + * Copyright (C) 2019 Benjamin Valentin + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup boards_stm32f030f4-demo + * @{ + * + * @file + * @brief Board initialization code for the stm32f030f4-demo board. + * + * @author Benjamin Valentin + * + * @} + */ + +#include "board.h" +#include "cpu.h" +#include "periph/gpio.h" + +void board_init(void) +{ + cpu_init(); + gpio_init(LED0_PIN, GPIO_OUT); + LED0_OFF; +} diff --git a/boards/stm32f030f4-demo/doc.txt b/boards/stm32f030f4-demo/doc.txt new file mode 100644 index 0000000000..24cd04710d --- /dev/null +++ b/boards/stm32f030f4-demo/doc.txt @@ -0,0 +1,54 @@ +/** +@defgroup boards_stm32f030f4-demo STM32F030F4 Demo Board +@ingroup boards +@brief Support for the STM32F030F4 Demo Board + +## Overview + +The STM32F030F4 Demo Board is a very cheap breakout board for the STM32F030F4 MCU. + +## Hardware + +![STM32F030F4 Demo Board](https://user-images.githubusercontent.com/20950920/48240567-e985c080-e3db-11e8-8775-68a216485b59.jpg) + +### MCU +| MCU | STM32F030R4 | +|:---------- |:--------------------- | +| Family | ARM Cortex-M0 | +| Vendor | ST Microelectronics | +| RAM | 4Kb | +| Flash | 16Kb | +| Frequency | up to 48MHz | +| FPU | no | +| Timers | 8 (2x watchdog, 1 SysTick, 5x 16-bit) | +| ADCs | 1x 12-bit | +| UARTs | 6 | +| SPIs | 1 | +| I2Cs | 1 | +| RTC | 1 | +| Vcc | 2.0V - 3.6V | +| Datasheet | [Datasheet](https://www.st.com/en/microcontrollers-microprocessors/stm32f030f4.html) | +| Reference Manual | [Reference Manual](https://www.st.com/resource/en/datasheet/stm32f030f4.pdf) | +| Programming Manual | [Programming Manual](http://www.st.com/resource/en/programming_manual/dm00051352.pdf) | + +## Flashing the device +The STM32F030F4 Demo Board board does not include a programmer. +You have to connect a separate ST-Link programmer to the (SW)DIO, (SW)CLK, GND and +NRST pins on the board. + +If you want a serial terminal, you have to connect a separate USB-Serial adapter to +the RX and TX pins on the board. + +The easiest way to program the board is to use OpenOCD. Once you have installed +OpenOCD (look [here](https://github.com/RIOT-OS/RIOT/wiki/OpenOCD) for +installation instructions), you can flash the board simply by typing + +``` +make BOARD=stm32f030f4-demo flash +``` +and debug via GDB by simply typing +``` +make BOARD=stm32f030f4-demo debug +``` + + */ diff --git a/boards/stm32f030f4-demo/include/board.h b/boards/stm32f030f4-demo/include/board.h new file mode 100644 index 0000000000..dcf94554bc --- /dev/null +++ b/boards/stm32f030f4-demo/include/board.h @@ -0,0 +1,61 @@ +/* + * Copyright (C) 2019 Benjamin Valentin + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup boards_stm32f030f4-demo + * + * This board can be bought very cheaply (< 1€) on sites like eBay or + * AliExpress. + * + * @brief Support for the STM32F030F4 Demo Board + * @{ + * + * @file + * @brief Pin definitions and board configuration options + * + * @author Benjamin Valentin + */ + +#ifndef BOARD_H +#define BOARD_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Xtimer configuration + * @{ + */ +#define XTIMER_WIDTH (16) +/** @} */ + +/** + * @name LED pin definitions and handlers + * @{ + */ +#define LED0_PORT GPIOA +#define LED0_PIN GPIO_PIN(PORT_A, 4) +#define LED0_MASK (1 << 4) + +#define LED0_ON (LED0_PORT->BSRR = (LED0_MASK << 16)) +#define LED0_OFF (LED0_PORT->BSRR = (LED0_MASK << 0)) +#define LED0_TOGGLE (LED0_PORT->ODR ^= LED0_MASK) +/** @} */ + +/** + * @brief Initialize board specific hardware, including clock, LEDs and std-IO + */ +void board_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /* BOARD_H */ +/** @} */ diff --git a/boards/stm32f030f4-demo/include/periph_conf.h b/boards/stm32f030f4-demo/include/periph_conf.h new file mode 100644 index 0000000000..e02cf2f319 --- /dev/null +++ b/boards/stm32f030f4-demo/include/periph_conf.h @@ -0,0 +1,189 @@ +/* + * Copyright (C) 2016 Inria + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup boards_stm32f030f4-demo + * @{ + * + * @file + * @brief Peripheral MCU configuration for the stm32f030f4-demo board + * + * @author Hauke Petersen + * @author José Ignacio Alamos + * @author Alexandre Abadie + * @author Benjamin Valentin + */ + +#ifndef PERIPH_CONF_H +#define PERIPH_CONF_H + +#include "periph_cpu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Clock settings + * + * @note This is auto-generated from + * `cpu/stm32_common/dist/clk_conf/clk_conf.c` + * @{ + */ +/* give the target core clock (HCLK) frequency [in Hz], + * maximum: 48MHz */ + #define CLOCK_CORECLOCK (48000000U) + /* 0: no external high speed crystal available + * else: actual crystal frequency [in Hz] */ + #define CLOCK_HSE (8000000U) + /* 0: no external low speed crystal available, + * 1: external crystal available (always 32.768kHz) */ + #define CLOCK_LSE (0) + /* peripheral clock setup */ + #define CLOCK_AHB_DIV RCC_CFGR_HPRE_DIV1 + #define CLOCK_AHB (CLOCK_CORECLOCK / 1) + #define CLOCK_APB1_DIV RCC_CFGR_PPRE_DIV1 /* max 48MHz */ + #define CLOCK_APB1 (CLOCK_CORECLOCK / 1) + #define CLOCK_APB2 (CLOCK_APB1) + + /* PLL factors */ + #define CLOCK_PLL_PREDIV (1) + #define CLOCK_PLL_MUL (6) + /** @} */ + +/** + * @name Timer configuration + * @{ + */ +static const timer_conf_t timer_config[] = { + { + .dev = TIM1, + .max = 0x0000ffff, + .rcc_mask = RCC_APB2ENR_TIM1EN, + .bus = APB2, + .irqn = TIM1_CC_IRQn + }, + { + .dev = TIM3, + .max = 0x0000ffff, + .rcc_mask = RCC_APB1ENR_TIM3EN, + .bus = APB1, + .irqn = TIM3_IRQn + }, +}; + +#define TIMER_0_ISR (isr_tim1_cc) +#define TIMER_1_ISR (isr_tim3) + +#define TIMER_NUMOF ARRAY_SIZE(timer_config) +/** @} */ + +/** + * @name UART configuration + * @{ + */ +static const uart_conf_t uart_config[] = { + { + .dev = USART1, + .rcc_mask = RCC_APB2ENR_USART1EN, + .rx_pin = GPIO_PIN(PORT_A, 10), + .tx_pin = GPIO_PIN(PORT_A, 9), + .rx_af = GPIO_AF1, + .tx_af = GPIO_AF1, + .bus = APB2, + .irqn = USART1_IRQn + } +}; + +#define UART_0_ISR (isr_usart1) + +#define UART_NUMOF ARRAY_SIZE(uart_config) +/** @} */ + +/** + * @name PWM configuration + * @{ + */ +static const pwm_conf_t pwm_config[] = { + { + .dev = TIM3, + .rcc_mask = RCC_APB1ENR_TIM3EN, + .chan = { { .pin = GPIO_PIN(PORT_A, 6), .cc_chan = 0}, + { .pin = GPIO_PIN(PORT_A, 7), .cc_chan = 1}, + { .pin = GPIO_UNDEF, .cc_chan = 0}, + { .pin = GPIO_UNDEF, .cc_chan = 0} }, + .af = GPIO_AF1, + .bus = APB1 + } +}; + +#define PWM_NUMOF ARRAY_SIZE(pwm_config) +/** @} */ + +/** + * @name SPI configuration + * + * @note The spi_divtable is auto-generated from + * `cpu/stm32_common/dist/spi_divtable/spi_divtable.c` + * @{ + */ +static const uint8_t spi_divtable[2][5] = { + { /* for APB1 @ 48000000Hz */ + 7, /* -> 187500Hz */ + 6, /* -> 375000Hz */ + 5, /* -> 750000Hz */ + 2, /* -> 6000000Hz */ + 1 /* -> 12000000Hz */ + }, + { /* for APB2 @ 48000000Hz */ + 7, /* -> 187500Hz */ + 6, /* -> 375000Hz */ + 5, /* -> 750000Hz */ + 2, /* -> 6000000Hz */ + 1 /* -> 12000000Hz */ + } +}; + +static const spi_conf_t spi_config[] = { + { + .dev = SPI1, + .mosi_pin = GPIO_PIN(PORT_A, 7), + .miso_pin = GPIO_PIN(PORT_A, 6), + .sclk_pin = GPIO_PIN(PORT_A, 5), + .cs_pin = GPIO_PIN(PORT_B, 1), + .af = GPIO_AF0, + .rccmask = RCC_APB2ENR_SPI1EN, + .apbbus = APB2 + }, +}; + +#define SPI_NUMOF ARRAY_SIZE(spi_config) +/** @} */ + +/** + * @name ADC configuration + * @{ + */ +#define ADC_CONFIG { \ + { GPIO_PIN(PORT_A, 0), 0 }, \ + { GPIO_PIN(PORT_A, 1), 1 }, \ + { GPIO_PIN(PORT_A, 2), 2 }, \ + { GPIO_PIN(PORT_A, 3), 3 }, \ + { GPIO_PIN(PORT_A, 4), 4 },\ + { GPIO_PIN(PORT_A, 5), 5 } \ +} + +#define ADC_NUMOF (6) +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H */ +/** @} */ diff --git a/cpu/stm32f0/include/cpu_conf.h b/cpu/stm32f0/include/cpu_conf.h index 0351236f4f..824885469f 100644 --- a/cpu/stm32f0/include/cpu_conf.h +++ b/cpu/stm32f0/include/cpu_conf.h @@ -38,7 +38,7 @@ extern "C" { #define CPU_DEFAULT_IRQ_PRIO (1U) #if defined(CPU_LINE_STM32F030x8) #define CPU_IRQ_NUMOF (29U) -#elif defined(CPU_LINE_STM32F031x6) +#elif defined(CPU_LINE_STM32F031x6) || defined(CPU_LINE_STM32F030x4) #define CPU_IRQ_NUMOF (28U) #elif defined(CPU_LINE_STM32F051x8) || defined(CPU_LINE_STM32F091xC) #define CPU_IRQ_NUMOF (31U) @@ -58,7 +58,8 @@ extern "C" { #if defined(CPU_LINE_STM32F091xC) || defined(CPU_LINE_STM32F072xB) #define FLASHPAGE_SIZE (2048U) #elif defined(CPU_LINE_STM32F051x8) || defined(CPU_LINE_STM32F042x6) \ - || defined(CPU_LINE_STM32F070xB) || defined(CPU_LINE_STM32F030x8) + || defined(CPU_LINE_STM32F070xB) || defined(CPU_LINE_STM32F030x8) \ + || defined(CPU_LINE_STM32F030x4) #define FLASHPAGE_SIZE (1024U) #endif diff --git a/cpu/stm32f0/include/vendor/stm32f030x4.h b/cpu/stm32f0/include/vendor/stm32f030x4.h new file mode 100644 index 0000000000..e624f968ac --- /dev/null +++ b/cpu/stm32f0/include/vendor/stm32f030x4.h @@ -0,0 +1,5368 @@ +/** + ****************************************************************************** + * @file stm32f030x4.h + * @author MCD Application Team + * @brief CMSIS Cortex-M0 Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for STM32F0xx devices. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f030x4 + * @{ + */ + +#ifndef __STM32F030x4_H +#define __STM32F030x4_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + + /** @addtogroup Configuration_section_for_CMSIS + * @{ + */ +/** + * @brief Configuration of the Cortex-M0 Processor and Core Peripherals + */ +#define __CM0_REV 0 /*!< Core Revision r0p0 */ +#define __MPU_PRESENT 0 /*!< STM32F0xx do not provide MPU */ +#define __NVIC_PRIO_BITS 2 /*!< STM32F0xx uses 2 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F0xx Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ + + /*!< Interrupt Number Definition */ +typedef enum +{ +/****** Cortex-M0 Processor Exceptions Numbers **************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M0 Hard Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M0 System Tick Interrupt */ + +/****** STM32F0 specific Interrupt Numbers ******************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + RTC_IRQn = 2, /*!< RTC Interrupt through EXTI Lines 17, 19 and 20 */ + FLASH_IRQn = 3, /*!< FLASH global Interrupt */ + RCC_IRQn = 4, /*!< RCC global Interrupt */ + EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupt */ + EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupt */ + EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupt */ + DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupt */ + DMA1_Channel4_5_IRQn = 11, /*!< DMA1 Channel 4 and Channel 5 Interrupt */ + ADC1_IRQn = 12, /*!< ADC1 Interrupt */ + TIM1_BRK_UP_TRG_COM_IRQn = 13, /*!< TIM1 Break, Update, Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 14, /*!< TIM1 Capture Compare Interrupt */ + TIM3_IRQn = 16, /*!< TIM3 global Interrupt */ + TIM14_IRQn = 19, /*!< TIM14 global Interrupt */ + TIM16_IRQn = 21, /*!< TIM16 global Interrupt */ + TIM17_IRQn = 22, /*!< TIM17 global Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Event Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 global Interrupt */ + USART1_IRQn = 27 /*!< USART1 global Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm0.h" /* Cortex-M0 processor and core peripherals */ +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC interrupt and status register, Address offset: 0x00 */ + __IO uint32_t IER; /*!< ADC interrupt enable register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ + __IO uint32_t CFGR1; /*!< ADC configuration register 1, Address offset: 0x0C */ + __IO uint32_t CFGR2; /*!< ADC configuration register 2, Address offset: 0x10 */ + __IO uint32_t SMPR; /*!< ADC sampling time register, Address offset: 0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t TR; /*!< ADC analog watchdog 1 threshold register, Address offset: 0x20 */ + uint32_t RESERVED3; /*!< Reserved, 0x24 */ + __IO uint32_t CHSELR; /*!< ADC group regular sequencer register, Address offset: 0x28 */ + uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */ + __IO uint32_t DR; /*!< ADC group regular data register, Address offset: 0x40 */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; /*!< ADC common configuration register, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t RESERVED3; /*!< Reserved, 0x14 */ +} CRC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +} DMA_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!