aboutsummaryrefslogtreecommitdiffstats
path: root/src/stm32f0
diff options
context:
space:
mode:
Diffstat (limited to 'src/stm32f0')
-rw-r--r--src/stm32f0/Kconfig42
-rw-r--r--src/stm32f0/Makefile67
-rw-r--r--src/stm32f0/adc.c164
-rw-r--r--src/stm32f0/can.c217
-rw-r--r--src/stm32f0/can.h17
-rw-r--r--src/stm32f0/gpio.c141
-rw-r--r--src/stm32f0/internal.h16
-rw-r--r--src/stm32f0/log.c79
-rw-r--r--src/stm32f0/log.h18
-rw-r--r--src/stm32f0/main.c201
-rw-r--r--src/stm32f0/serial.c98
-rw-r--r--src/stm32f0/stm32f0.ld111
-rw-r--r--src/stm32f0/stm32f0xx_hal_conf.h336
-rw-r--r--src/stm32f0/timer.c156
14 files changed, 1663 insertions, 0 deletions
diff --git a/src/stm32f0/Kconfig b/src/stm32f0/Kconfig
new file mode 100644
index 00000000..faab5b94
--- /dev/null
+++ b/src/stm32f0/Kconfig
@@ -0,0 +1,42 @@
+# Kconfig settings for STM32F0 processors
+
+if MACH_STM32F0
+
+config STM32F0_SELECT
+ bool
+ default y
+ select HAVE_GPIO
+ select HAVE_GPIO_ADC
+ select HAVE_GPIO_BITBANGING
+
+config BOARD_DIRECTORY
+ string
+ default "stm32f0"
+
+config CLOCK_FREQ
+ int
+ default 48000000
+
+config CANSERIAL
+ bool "Use CAN bus for communication (instead of serial)"
+ default y
+config SERIAL
+ depends on !CANSERIAL
+ bool
+ default y
+
+config SERIAL_BAUD
+ int "CAN bus speed" if LOW_LEVEL_OPTIONS && CANSERIAL
+ default 500000 if CANSERIAL
+
+config DEBUG_OUT
+ bool "Use debug output to UART TX pin"
+ depends on CANSERIAL
+ default y
+
+config USE_LOG
+ string
+ default "USE_LOG" if DEBUG_OUT
+ default "NO_LOG" if !DEBUG_OUT
+
+endif
diff --git a/src/stm32f0/Makefile b/src/stm32f0/Makefile
new file mode 100644
index 00000000..7044b5c4
--- /dev/null
+++ b/src/stm32f0/Makefile
@@ -0,0 +1,67 @@
+# Additional STM32F0 build rules
+
+STLINK=st-flash
+
+# Setup the toolchain
+CROSS_PREFIX=arm-none-eabi-
+
+dirs-y += src/stm32f0 src/generic
+dirs-y += lib/cmsis-stm32f0/source
+dirs-y += lib/hal-stm32f0/source
+
+CFLAGS = -I$(OUT) -Isrc -I$(OUT)board-generic/ -std=gnu11 -O2 -MD \
+ -Wall -Wold-style-definition $(call cc-option,$(CC),-Wtype-limits,) \
+ -ffunction-sections -fdata-sections
+CFLAGS += -flto -fno-use-linker-plugin
+CFLAGS += -mthumb -mcpu=cortex-m0 -g3
+CFLAGS += -Ilib/cmsis-core -Iout/board
+CFLAGS += -Ilib/cmsis-stm32f0/include -Ilib/cmsis-stm32f0
+CFLAGS += -Ilib/hal-stm32f0/include
+CFLAGS += -DSTM32F042x6 -DUSE_HAL_DRIVER
+
+# Add source files
+src-y += stm32f0/main.c stm32f0/timer.c stm32f0/gpio.c
+src-$(CONFIG_CANSERIAL) += stm32f0/can.c
+src-$(CONFIG_DEBUG_OUT) += stm32f0/log.c
+src-$(CONFIG_SERIAL) += stm32f0/serial.c
+src-y += generic/serial_irq.c
+src-$(CONFIG_HAVE_GPIO_ADC) += stm32f0/adc.c
+src-y += $(addprefix ../, $(wildcard lib/hal-stm32f0/source/stm32f0xx_*.c))
+src-y += generic/crc16_ccitt.c generic/armcm_irq.c
+src-y += ../lib/cmsis-stm32f0/source/system_stm32f0xx.c
+
+# Add assembler build rules
+$(OUT)%.o: %.s $(OUT)autoconf.h $(OUT)board-link
+ @echo " Assembling $@"
+ $(Q)$(AS) $< -o $@
+
+asmsrc-y = ../lib/cmsis-stm32f0/source/startup_stm32f042x6.s
+OBJS_klipper.elf += $(patsubst %.s, $(OUT)src/%.o,$(asmsrc-y))
+
+# Build the linker script
+$(OUT)stm32f0.ld: src/stm32f0/stm32f0.ld $(OUT)board-link
+ @echo " Preprocessing $@"
+ $(Q)$(CPP) -P -MD -MT $@ -DFLASH_START=$(CONFIG_FLASH_START) $< -o $@
+
+CFLAGS_klipper.elf += -T $(OUT)stm32f0.ld
+CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
+$(OUT)klipper.elf : $(OUT)stm32f0.ld
+
+# Binary output file rules
+target-y += $(OUT)klipper.bin
+
+$(OUT)klipper.bin: $(OUT)klipper.elf
+ @echo " Creating binary file $@"
+ $(Q)$(OBJCOPY) -O binary $< $@
+
+$(OUT)klipper.hex: $(OUT)klipper.elf
+ @echo " Creating hex file $@"
+ $(Q)$(OBJCOPY) -O ihex $< $@
+
+flash: $(OUT)klipper.hex
+ @echo " Flashing hex file $<"
+ $(Q)$(STLINK) --format ihex --reset write $<
+
+debug: $(OUT)klipper.hex
+ @echo " Remote debug:"
+ openocd -f interface/stlink.cfg -f target/stm32f0x.cfg
diff --git a/src/stm32f0/adc.c b/src/stm32f0/adc.c
new file mode 100644
index 00000000..e4a4213c
--- /dev/null
+++ b/src/stm32f0/adc.c
@@ -0,0 +1,164 @@
+/*
+ * ADC functions on STM32F0
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ */
+
+#include <stdbool.h> // bool
+#include "board/gpio.h" // gpio_adc_setup
+#include "board/io.h" // readb
+#include "stm32f0xx_hal.h"
+#include "internal.h" // GPIO
+#include "compiler.h" // ARRAY_SIZE
+#include "command.h" // shutdown
+#include "sched.h" // sched_shutdown
+
+DECL_CONSTANT("ADC_MAX", 4095);
+
+#define ADC_DELAY (240 * 8)
+static bool adc_busy;
+static uint8_t adc_current_channel;
+ADC_HandleTypeDef hadc;
+
+static const uint8_t adc_pins[] = {
+ GPIO('A', 0), GPIO('A', 1),
+#if !(CONFIG_SERIAL)
+ GPIO('A', 2), GPIO('A', 3),
+#endif
+ GPIO('A', 4), GPIO('A', 5), GPIO('A', 6), GPIO('A', 7),
+ GPIO('B', 1),
+ // Fake ADC on this GPIO (returns tempsensor value)
+ GPIO('B', 8)
+};
+
+static const uint32_t adc_channels[] = {
+ ADC_CHANNEL_0,
+ ADC_CHANNEL_1,
+#if !(CONFIG_SERIAL)
+ ADC_CHANNEL_2,
+ ADC_CHANNEL_3,
+#endif
+ ADC_CHANNEL_4,
+ ADC_CHANNEL_5,
+ ADC_CHANNEL_6,
+ ADC_CHANNEL_7,
+ ADC_CHANNEL_9,
+ // For tests
+ ADC_CHANNEL_TEMPSENSOR
+};
+
+struct gpio_adc
+gpio_adc_setup(uint8_t pin)
+{
+ // Find pin in adc_pins table
+ int chan;
+ ADC_ChannelConfTypeDef sConfig = {0};
+ for (chan=0; ; chan++) {
+ if (chan >= ARRAY_SIZE(adc_pins))
+ shutdown("Not a valid ADC pin");
+ if (adc_pins[chan] == pin) {
+ sConfig.Channel = adc_channels[chan];
+ break;
+ }
+ }
+
+ /**ADC GPIO Configuration
+ */
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ GPIO_InitStruct.Pin = 1 << (pin % 16);;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init((pin<8)?GPIOA:GPIOB, &GPIO_InitStruct);
+ /**Configure for the selected ADC regular channel to be converted.
+ */
+ sConfig.Rank = ADC_RANK_CHANNEL_NUMBER;
+ sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5;
+ HAL_ADC_ConfigChannel(&hadc, &sConfig);
+ HAL_ADCEx_Calibration_Start(&hadc);
+ return (struct gpio_adc){ .pin = adc_channels[chan] };
+}
+
+// Try to sample a value. Returns zero if sample ready, otherwise
+// returns the number of clock ticks the caller should wait before
+// retrying this function.
+uint32_t
+gpio_adc_sample(struct gpio_adc g)
+{
+ /* ADC not busy, start conversion */
+ if (!readb(&adc_busy)) {
+ HAL_ADC_Start(&hadc);
+ adc_busy = true;
+ adc_current_channel = g.pin;
+ return ADC_DELAY;
+ /* ADC finished conversion for this channel */
+ } else if (HAL_ADC_PollForConversion(&hadc, 100) == HAL_OK) {
+ __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_EOS);
+ adc_busy = false;
+ return 0;
+ }
+ /* Wants to sample another channel, or not finished yet */
+ return ADC_DELAY;
+}
+
+// Read a value; use only after gpio_adc_sample() returns zero
+uint16_t
+gpio_adc_read(struct gpio_adc g)
+{
+ return HAL_ADC_GetValue(&hadc);
+}
+
+// Cancel a sample that may have been started with gpio_adc_sample()
+void
+gpio_adc_cancel_sample(struct gpio_adc g)
+{
+ if (readb(&adc_busy) && readl(&adc_current_channel) == g.pin) {
+ adc_busy = false;
+ HAL_ADC_Stop(&hadc);
+ }
+}
+
+/**
+ * @brief ADC Initialization Function
+ * @param None
+ * @retval None
+ */
+void AdcInit(void)
+{
+ /**Configure the global features of the ADC (Clock,
+ * Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = ADC1;
+ hadc.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
+ hadc.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.ScanConvMode = ADC_SCAN_DIRECTION_FORWARD;
+ hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc.Init.LowPowerAutoWait = DISABLE;
+ hadc.Init.LowPowerAutoPowerOff = DISABLE;
+ hadc.Init.ContinuousConvMode = DISABLE;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START;
+ hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc.Init.DMAContinuousRequests = DISABLE;
+ hadc.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
+ HAL_ADC_Init(&hadc);
+}
+DECL_INIT(AdcInit);
+
+
+/**
+* @brief ADC MSP Initialization
+* @param hadc: ADC handle pointer
+* @retval None
+*/
+void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)
+{
+ if(hadc->Instance==ADC1)
+ {
+ /* Peripheral clock enable */
+ __HAL_RCC_ADC1_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ }
+}
diff --git a/src/stm32f0/can.c b/src/stm32f0/can.c
new file mode 100644
index 00000000..6ce9aad4
--- /dev/null
+++ b/src/stm32f0/can.c
@@ -0,0 +1,217 @@
+/*
+ * Serial over CAN emulation for STM32F042 boards.
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ */
+
+#include "stm32f0xx_hal.h"
+#include <string.h>
+#include "can.h"
+#include "command.h" // encoder
+#include "board/serial_irq.h" // serial_enable_tx_irq
+#include "sched.h" // DECL_INIT
+#include "log.h"
+
+CAN_HandleTypeDef hcan;
+CanTxMsgTypeDef TxMessage;
+CanRxMsgTypeDef RxMessage;
+static uint16_t MyCanId = 0;
+
+
+void CanTransmit(uint32_t id, uint32_t dlc, uint8_t *pkt)
+{
+ memcpy(hcan.pTxMsg->Data, pkt, dlc);
+ hcan.pTxMsg->StdId = id;
+ hcan.pTxMsg->DLC = dlc;
+ HAL_CAN_Transmit_IT(&hcan);
+}
+
+// Convert Unique 96-bit value into 48 bit representation
+static void PackUuid(uint8_t* u)
+{
+ for(int i=0; i<SHORT_UUID_LEN; i++) {
+ u[i] = *((uint8_t*)(STM32_UUID_ADDR+i)) ^
+ *((uint8_t*)(STM32_UUID_ADDR+i+SHORT_UUID_LEN));
+ }
+}
+
+static void CanUUIDResp(void)
+{
+ uint8_t short_uuid[SHORT_UUID_LEN];
+ PackUuid(short_uuid);
+ CanTransmit(PKT_ID_UUID_RESP, SHORT_UUID_LEN, short_uuid);
+}
+
+void CanInit(void)
+{
+ // Master reset
+ //SET_BIT(CAN->MCR, CAN_MCR_RESET);
+
+ hcan.Instance = CAN;
+ hcan.Init.Prescaler = 12;
+ hcan.Init.Mode = CAN_MODE_NORMAL;
+ hcan.Init.SJW = CAN_SJW_1TQ;
+ hcan.Init.BS1 = CAN_BS1_5TQ;
+ hcan.Init.BS2 = CAN_BS2_2TQ;
+ hcan.Init.TTCM = DISABLE;
+ hcan.Init.ABOM = DISABLE;
+ hcan.Init.AWUM = DISABLE;
+ hcan.Init.NART = ENABLE;
+ hcan.Init.RFLM = DISABLE;
+ hcan.Init.TXFP = DISABLE;
+ HAL_CAN_Init(&hcan);
+ hcan.pTxMsg = &TxMessage;
+ hcan.pRxMsg = &RxMessage;
+
+ /*##-2- Configure the CAN Filter #######################################*/
+ CAN_FilterConfTypeDef sFilterConfig;
+ sFilterConfig.FilterNumber = 0;
+ sFilterConfig.FilterMode = CAN_FILTERMODE_IDLIST;
+ sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
+ sFilterConfig.FilterIdHigh = PKT_ID_UUID<<5;
+ sFilterConfig.FilterIdLow = 0x0000;
+ sFilterConfig.FilterMaskIdHigh = PKT_ID_SET<<5;
+ sFilterConfig.FilterMaskIdLow = 0x0000;
+ sFilterConfig.FilterFIFOAssignment = CAN_FIFO0;
+ sFilterConfig.FilterActivation = ENABLE;
+ HAL_CAN_ConfigFilter(&hcan, &sFilterConfig);
+
+ /*##-3- Configure Transmission process #################################*/
+ hcan.pTxMsg->ExtId = 0;
+ HAL_CAN_Receive_IT(&hcan, CAN_FIFO0);
+
+ /* Request for port */
+ CanUUIDResp();
+}
+DECL_INIT(CanInit);
+
+void HAL_CAN_RxCpltCallback(CAN_HandleTypeDef* h) {
+ int i;
+
+ if(!MyCanId) { // If serial not assigned yet
+ if(h->pRxMsg->StdId == PKT_ID_UUID && h->pRxMsg->DLC == 0) {
+ // Just inform host about my UUID
+ CanUUIDResp();
+ } else if (h->pRxMsg->StdId == PKT_ID_SET) {
+ // compare my UUID with packet to check if this packet mine
+ uint8_t short_uuid[SHORT_UUID_LEN];
+ PackUuid(short_uuid);
+ if (memcmp(&(h->pRxMsg->Data[2]), short_uuid,
+ SHORT_UUID_LEN) == 0) {
+ memcpy(&MyCanId, h->pRxMsg->Data, sizeof(uint16_t));
+ CAN_FilterConfTypeDef sFilterConfig;
+ sFilterConfig.FilterNumber = 0;
+ sFilterConfig.FilterMode = CAN_FILTERMODE_IDLIST;
+ sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
+ // Personal ID
+ sFilterConfig.FilterIdHigh = MyCanId<<5;
+ sFilterConfig.FilterIdLow = 0x0000;
+ // Catch reset command
+ sFilterConfig.FilterMaskIdHigh = PKT_ID_UUID<<5;
+ sFilterConfig.FilterMaskIdLow = 0x0000;
+ sFilterConfig.FilterFIFOAssignment = CAN_FIFO0;
+ sFilterConfig.FilterActivation = ENABLE;
+ // Disable 'set address' filter and enable only my packets
+ HAL_CAN_ConfigFilter(&hcan, &sFilterConfig);
+ }
+ }
+ } else {
+ if(h->pRxMsg->StdId == MyCanId) {
+ if(h->pRxMsg->DLC == 0) {
+ // empty packet == ping request
+ hcan.pTxMsg->StdId = MyCanId+1;
+ hcan.pTxMsg->DLC = 0;
+ HAL_CAN_Transmit_IT(&hcan);
+ } else {
+ for(i=0; i < h->pRxMsg->DLC; i++ ) {
+ serial_rx_byte(h->pRxMsg->Data[i]);
+ }
+ }
+ } else if (h->pRxMsg->StdId == PKT_ID_UUID && h->pRxMsg->DLC > 0) {
+ if (memcmp(&(h->pRxMsg->Data), &MyCanId, 2) == 0) {
+ // Reset from host
+ NVIC_SystemReset();
+ }
+ }
+ }
+ HAL_CAN_Receive_IT(&hcan, CAN_FIFO0);
+}
+
+void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *h)
+{
+ // Overrun handling - drop damaged packet
+ HAL_CAN_Receive_IT(&hcan, CAN_FIFO0);
+}
+
+/**
+ * @brief This function handles HDMI-CEC and CAN global interrupts /
+ * HDMI-CEC wake-up interrupt through EXTI line 27.
+ */
+void CEC_CAN_IRQHandler(void)
+{
+ HAL_CAN_IRQHandler(&hcan);
+}
+
+void
+serial_enable_tx_irq(void)
+{
+ if(MyCanId == 0)
+ // Serial port not initialized
+ return;
+
+ int i=0;
+ for (;i<8;)
+ {
+ if(serial_get_tx_byte(&(hcan.pTxMsg->Data[i])) == -1) {
+ break;
+ }
+ i++;
+ }
+ if (i>0) {
+ hcan.pTxMsg->StdId = MyCanId+1;
+ hcan.pTxMsg->DLC = i;
+ HAL_CAN_Transmit_IT(&hcan);
+ }
+}
+
+void HAL_CAN_TxCpltCallback(CAN_HandleTypeDef* hcan)
+{
+ // if we still have some data to transmit
+ serial_enable_tx_irq();
+}
+
+/*
+ * @brief CAN MSP Initialization
+ * @param h: CAN handle pointer
+ * @retval None
+ */
+void HAL_CAN_MspInit(CAN_HandleTypeDef* h)
+{
+
+ __HAL_REMAP_PIN_ENABLE(HAL_REMAP_PA11_PA12);
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(h->Instance==CAN)
+ {
+ /* Peripheral clock enable */
+ __HAL_RCC_CAN1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**CAN GPIO Configuration
+ PA11 ------> CAN_RX
+ PA12 ------> CAN_TX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF4_CAN;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* CAN interrupt Init */
+ HAL_NVIC_SetPriority(CEC_CAN_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(CEC_CAN_IRQn);
+ }
+}
diff --git a/src/stm32f0/can.h b/src/stm32f0/can.h
new file mode 100644
index 00000000..6b3cb2a4
--- /dev/null
+++ b/src/stm32f0/can.h
@@ -0,0 +1,17 @@
+#ifndef CORE_INC_CAN_H_
+#define CORE_INC_CAN_H_
+
+// Read UUID (6bytes)
+#define PKT_ID_UUID (0x321)
+// Set address (2bytes) to UUID (6b)
+#define PKT_ID_SET (0x322)
+// UUID response from slave (6bytes)
+#define PKT_ID_UUID_RESP (0x323)
+
+#define STM32_UUID_ADDR (0x1FFFF7AC)
+#define SHORT_UUID_LEN (6)
+
+void CanInit(void);
+void CanTransmit(uint32_t id, uint32_t dlc, uint8_t *pkt);
+
+#endif /* CORE_INC_CAN_H_ */
diff --git a/src/stm32f0/gpio.c b/src/stm32f0/gpio.c
new file mode 100644
index 00000000..74e2fb9e
--- /dev/null
+++ b/src/stm32f0/gpio.c
@@ -0,0 +1,141 @@
+/*
+ * GPIO functions on STM32F042 boards.
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ */
+
+#include "board/gpio.h" // gpio_out_setup
+#include "stm32f0xx_hal.h"
+#include "internal.h" // GPIO
+#include "board/irq.h" // irq_save
+#include "compiler.h" // ARRAY_SIZE
+#include "sched.h" // sched_shutdown
+#include "command.h" // shutdown
+
+DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 11);
+DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 9);
+DECL_ENUMERATION_RANGE("pin", "PF0", GPIO('F', 0), 2);
+
+GPIO_TypeDef *const digital_regs[] = {
+ GPIOA, GPIOB, GPIOC, GPIOF
+};
+
+// <port:4><pin:4>
+uint8_t const avail_pins[] = {
+ 0x0 + 0x0, //PA0
+ 0x0 + 0x1, //PA1
+#if !(CONFIG_SERIAL)
+ 0x0 + 0x2, //PA2 - USART pins
+ 0x0 + 0x3, //PA3
+#endif
+ 0x0 + 0x4, //PA4
+ 0x0 + 0x5, //PA5
+ 0x0 + 0x6, //PA6
+ 0x0 + 0x7, //PA7
+#if !(CONFIG_CANSERIAL)
+ 0x0 + 0x9, //PA9 - but remapped in CAN mode to PA11,PA12
+ 0x0 + 0xa, //PA10
+#endif
+ 0x10 + 0x1, //PB1
+ 0x10 + 0x8, //PB8
+ 0x50 + 0x0, //PF0
+ 0x50 + 0x1, //PF1
+};
+
+/****************************************************************
+ * General Purpose Input Output (GPIO) pins
+ ****************************************************************/
+
+static uint8_t
+gpio_check_pin(uint8_t pin)
+{
+ int i;
+ for(i=0; i<ARRAY_SIZE(avail_pins); i++) {
+ if (avail_pins[i] == pin)
+ return i;
+ }
+ return 0xFF;
+}
+
+struct gpio_out
+gpio_out_setup(uint8_t pin, uint8_t val)
+{
+ struct gpio_out g = { .pin=pin };
+ if (gpio_check_pin(pin) < 0xFF) {
+ gpio_out_reset(g, val);
+ } else {
+ shutdown("Not an output pin");
+ }
+ return g;
+}
+
+void
+gpio_out_reset(struct gpio_out g, uint8_t val)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ GPIO_InitStruct.Pin = 1 << (g.pin % 16);
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ HAL_GPIO_Init(digital_regs[GPIO2PORT(g.pin)], &GPIO_InitStruct);
+ HAL_GPIO_WritePin(digital_regs[GPIO2PORT(g.pin)], 1 << (g.pin % 16), val);
+}
+
+void
+gpio_out_write(struct gpio_out g, uint8_t val)
+{
+ HAL_GPIO_WritePin(digital_regs[GPIO2PORT(g.pin)], 1 << (g.pin % 16), val);
+}
+
+struct gpio_in
+gpio_in_setup(uint8_t pin, int8_t pull_up)
+{
+ struct gpio_in g = { .pin=pin };
+ if (gpio_check_pin(pin) < 0xFF) {
+ gpio_in_reset(g, pull_up);
+ } else {
+ shutdown("Not an input pin");
+ }
+ return g;
+}
+
+void
+gpio_in_reset(struct gpio_in g, int8_t pull_up)
+{
+ irqstatus_t flag = irq_save();
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ GPIO_InitStruct.Pin = 1 << (g.pin % 16);
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = (pull_up)?GPIO_PULLUP:GPIO_NOPULL;
+ HAL_GPIO_Init(digital_regs[GPIO2PORT(g.pin)], &GPIO_InitStruct);
+ irq_restore(flag);
+}
+
+uint8_t
+gpio_in_read(struct gpio_in g)
+{
+ return HAL_GPIO_ReadPin(digital_regs[GPIO2PORT(g.pin)], 1 << (g.pin % 16));
+}
+
+void
+gpio_out_toggle_noirq(struct gpio_out g)
+{
+ HAL_GPIO_TogglePin(digital_regs[GPIO2PORT(g.pin)], 1 << (g.pin % 16));
+}
+
+void
+gpio_out_toggle(struct gpio_out g)
+{
+ irqstatus_t flag = irq_save();
+ gpio_out_toggle_noirq(g);
+ irq_restore(flag);
+}
+
+void gpio_init(void)
+{
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+}
diff --git a/src/stm32f0/internal.h b/src/stm32f0/internal.h
new file mode 100644
index 00000000..5247a9c7
--- /dev/null
+++ b/src/stm32f0/internal.h
@@ -0,0 +1,16 @@
+#ifndef __STM32F0_INTERNAL_H
+#define __STM32F0_INTERNAL_H
+// Local definitions for STM32F0 code
+
+#include "stm32f0xx.h"
+
+#define GPIO(PORT, NUM) (((PORT)-'A') * 16 + (NUM))
+#define GPIO2PORT(PIN) ((PIN) / 16)
+
+extern uint8_t const avail_pins[];
+
+void udelay(uint32_t usecs);
+void gpio_init(void);
+void TimerInit(void);
+
+#endif // internal.h
diff --git a/src/stm32f0/log.c b/src/stm32f0/log.c
new file mode 100644
index 00000000..cbfb00cf
--- /dev/null
+++ b/src/stm32f0/log.c
@@ -0,0 +1,79 @@
+/*
+ * log.c
+ * This file not required for regular Klipper usage, but hw/sw developer
+ * can use USART TX pin instead SWO for debugging purposes
+ *
+ * Created on: Jan 17, 2019
+ * Author: eug
+ */
+
+#include "string.h"
+#include "stm32f0xx_hal.h"
+#include "log.h"
+
+UART_HandleTypeDef huart2;
+
+void LogInit(void)
+{
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = 115200;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ HAL_UART_Init(&huart2);
+
+ lprint("hello");
+}
+
+/**
+* @brief String out
+* @param msg: Null-terminated string
+* @retval None
+*/
+void lprint(char *msg)
+{
+ HAL_UART_Transmit(&huart2, (uint8_t *)msg, strlen(msg), 100);
+}
+
+/**
+* @brief Binary data out
+* @param msg: binary data
+* @param len: data length
+* @retval None
+*/
+void lnprint(char *msg, size_t len)
+{
+ HAL_UART_Transmit(&huart2, (uint8_t *)msg, len, 100);
+}
+
+/**
+* @brief UART MSP Initialization
+* @param huart: UART handle pointer
+* @retval None
+*/
+void HAL_UART_MspInit(UART_HandleTypeDef* huart)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(huart->Instance==USART2)
+ {
+ __HAL_RCC_USART2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF1_USART2;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ }
+}
diff --git a/src/stm32f0/log.h b/src/stm32f0/log.h
new file mode 100644
index 00000000..fda8a9d8
--- /dev/null
+++ b/src/stm32f0/log.h
@@ -0,0 +1,18 @@
+/*
+ * log.h
+ *
+ * Created on: Jan 17, 2019
+ * Author: eug
+ */
+
+#ifndef CORE_INC_LOG_H_
+#define CORE_INC_LOG_H_
+
+
+void LogInit(void);
+
+void lprint(char *msg);
+void lnprint(char *msg, size_t len);
+
+
+#endif /* CORE_INC_LOG_H_ */
diff --git a/src/stm32f0/main.c b/src/stm32f0/main.c
new file mode 100644
index 00000000..89d8a6e5
--- /dev/null
+++ b/src/stm32f0/main.c
@@ -0,0 +1,201 @@
+/*
+ * Main starting point for STM32F042 boards.
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ */
+
+#include "stm32f0xx_hal.h"
+#include "autoconf.h"
+#include "command.h" // DECL_CONSTANT
+#include "board/misc.h" // timer_read_time
+#include "sched.h" // sched_main
+#include "internal.h"
+#include "can.h"
+#include "log.h"
+
+DECL_CONSTANT_STR("MCU","stm32f042");
+
+static IWDG_HandleTypeDef hiwdg;
+
+/****************************************************************
+ * dynamic memory pool
+ ****************************************************************/
+
+static char dynmem_pool[3 * 1024];
+
+// Return the start of memory available for dynamic allocations
+void *
+dynmem_start(void)
+{
+ return dynmem_pool;
+}
+
+// Return the end of memory available for dynamic allocations
+void *
+dynmem_end(void)
+{
+ return &dynmem_pool[sizeof(dynmem_pool)];
+}
+
+/****************************************************************
+ * misc functions
+ ****************************************************************/
+
+void
+command_reset(uint32_t *args)
+{
+ NVIC_SystemReset();
+}
+DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset");
+
+void clock_config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI
+ |RCC_OSCILLATORTYPE_HSI14|RCC_OSCILLATORTYPE_HSI48
+ |RCC_OSCILLATORTYPE_LSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
+ RCC_OscInitStruct.HSI14State = RCC_HSI14_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.HSI14CalibrationValue = 16;
+ RCC_OscInitStruct.LSIState = RCC_LSI_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
+ HAL_RCC_OscConfig(&RCC_OscInitStruct);
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI48;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+ HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1);
+
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_RTC;
+ PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_HSI;
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
+}
+
+// Implement simple early-boot delay mechanism
+void
+udelay(uint32_t usecs)
+{
+ uint32_t end = timer_read_time() + timer_from_us(usecs);
+ while (timer_is_before(timer_read_time(), end))
+ ;
+}
+
+void
+watchdog_reset(void)
+{
+ HAL_IWDG_Refresh(&hiwdg);
+}
+DECL_TASK(watchdog_reset);
+
+void
+watchdog_init(void)
+{
+ hiwdg.Instance = IWDG;
+ hiwdg.Init.Prescaler = IWDG_PRESCALER_16;
+ hiwdg.Init.Window = 4095;
+ hiwdg.Init.Reload = 4095;
+ //HAL_IWDG_Init(&hiwdg); ToDo enable after debug
+}
+DECL_INIT(watchdog_init);
+
+// Main entry point
+int
+main(void)
+{
+ HAL_Init();
+
+ clock_config();
+ gpio_init();
+#if (CONFIG_DEBUG_OUT)
+ LogInit();
+#endif
+ sched_main();
+ return 0;
+}
+
+void __attribute__((weak)) lprint(char *msg) {}
+void __attribute__((weak)) lnprint(char *msg, size_t len) {}
+
+/*
+ * MSP init functions ( __weak replacement )
+ */
+
+/*
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_RCC_WWDG_CLK_ENABLE();
+}
+
+/****************************************************************
+ * Debug helper (taken from https://community.arm.com/)
+ * In case of Hard Fault it helps to find fault reason
+ * on Cortex-M0 chips
+ ****************************************************************/
+
+void hard_fault_handler_c(unsigned long *hardfault_args){
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
+ volatile unsigned long stacked_r0 ;
+ volatile unsigned long stacked_r1 ;
+ volatile unsigned long stacked_r2 ;
+ volatile unsigned long stacked_r3 ;
+ volatile unsigned long stacked_r12 ;
+ volatile unsigned long stacked_lr ;
+ volatile unsigned long stacked_pc ;
+ volatile unsigned long stacked_psr ;
+ volatile unsigned long _CFSR ;
+ volatile unsigned long _HFSR ;
+ volatile unsigned long _DFSR ;
+ volatile unsigned long _AFSR ;
+ volatile unsigned long _BFAR ;
+ volatile unsigned long _MMAR ;
+
+ stacked_r0 = ((unsigned long)hardfault_args[0]) ;
+ stacked_r1 = ((unsigned long)hardfault_args[1]) ;
+ stacked_r2 = ((unsigned long)hardfault_args[2]) ;
+ stacked_r3 = ((unsigned long)hardfault_args[3]) ;
+ stacked_r12 = ((unsigned long)hardfault_args[4]) ;
+ stacked_lr = ((unsigned long)hardfault_args[5]) ;
+ stacked_pc = ((unsigned long)hardfault_args[6]) ;
+ stacked_psr = ((unsigned long)hardfault_args[7]) ;
+
+ // Configurable Fault Status Register
+ // Consists of MMSR, BFSR and UFSR
+ _CFSR = (*((volatile unsigned long *)(0xE000ED28))) ;
+
+ // Hard Fault Status Register
+ _HFSR = (*((volatile unsigned long *)(0xE000ED2C))) ;
+
+ // Debug Fault Status Register
+ _DFSR = (*((volatile unsigned long *)(0xE000ED30))) ;
+
+ // Auxiliary Fault Status Register
+ _AFSR = (*((volatile unsigned long *)(0xE000ED3C))) ;
+
+ // Read the Fault Address Registers. These may not contain valid values.
+ // Check BFARVALID/MMARVALID to see if they are valid values
+ // MemManage Fault Address Register
+ _MMAR = (*((volatile unsigned long *)(0xE000ED34))) ;
+ // Bus Fault Address Register
+ _BFAR = (*((volatile unsigned long *)(0xE000ED38))) ;
+
+ __asm("BKPT #0\n") ; // Break into the debugger
+#pragma GCC diagnostic pop
+}
diff --git a/src/stm32f0/serial.c b/src/stm32f0/serial.c
new file mode 100644
index 00000000..103a0d70
--- /dev/null
+++ b/src/stm32f0/serial.c
@@ -0,0 +1,98 @@
+/*
+ * Serial communication for STM32F042 boards.
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ */
+
+#include "stm32f0xx_hal.h"
+#include <string.h>
+#include "autoconf.h" // CONFIG_SERIAL_BAUD
+#include "board/serial_irq.h" // serial_rx_byte
+#include "sched.h" // DECL_INIT
+
+UART_HandleTypeDef huart2;
+static uint8_t rxbuf, txbuf;
+
+void USART2_IRQHandler(void)
+{
+ HAL_UART_IRQHandler(&huart2);
+}
+
+/**
+ * @brief USART2 Initialization Function
+ * @param None
+ * @retval None
+ */
+void UartInit(void)
+{
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = CONFIG_SERIAL_BAUD;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX_RX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ HAL_UART_Init(&huart2);
+
+ HAL_UART_Receive_IT(&huart2,&rxbuf,(uint16_t)1);
+}
+DECL_INIT(UartInit);
+
+void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
+{
+ if (huart == &huart2) {
+ serial_rx_byte(rxbuf);
+ HAL_UART_Receive_IT(&huart2,&rxbuf,(uint16_t)1);
+ }
+}
+
+void serial_enable_tx_irq(void)
+{
+ while(huart2.gState != HAL_UART_STATE_READY);
+ if(serial_get_tx_byte(&txbuf) == 0) {
+ HAL_UART_Transmit_IT(&huart2,&txbuf,(uint16_t)1);
+ }
+}
+
+void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart)
+{
+ if (huart == &huart2)
+ serial_enable_tx_irq();
+}
+
+/**
+* @brief UART MSP Initialization
+* @param huart: UART handle pointer
+* @retval None
+*/
+void HAL_UART_MspInit(UART_HandleTypeDef* huart)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(huart->Instance==USART2)
+ {
+ /* Peripheral clock enable */
+ __HAL_RCC_USART2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF1_USART2;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USART2 interrupt Init */
+ HAL_NVIC_SetPriority(USART2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(USART2_IRQn);
+ }
+}
diff --git a/src/stm32f0/stm32f0.ld b/src/stm32f0/stm32f0.ld
new file mode 100644
index 00000000..88851a5f
--- /dev/null
+++ b/src/stm32f0/stm32f0.ld
@@ -0,0 +1,111 @@
+/* Linker script for STM32F042F6Px Device with 32KByte FLASH, 6KByte RAM
+ This file is taken from lib/cmsis-stm32f0/source/STM32F042F6Px_FLASH.ld
+*/
+
+ENTRY(Reset_Handler)
+
+MEMORY
+{
+ FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 6K
+}
+
+/* highest address of the user mode stack */
+_estack = 0x20001800;
+
+SECTIONS
+{
+ /* Interrupt vector table */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector))
+ . = ALIGN(4);
+ } >FLASH
+
+ /* Program code and constant data */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text)
+ *(.text*)
+ *(.rodata)
+ *(.rodata*)
+ KEEP (*(.init))
+ KEEP (*(.fini))
+ . = ALIGN(4);
+ _etext = .;
+ } >FLASH
+
+ /* Exception handling */
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ /* Static constructor initialization (C++) */
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+
+ /* Initialized data, needs to be handled by startup code */
+ _sidata = .;
+ .data : AT (_sidata)
+ {
+ . = ALIGN(4);
+ _sdata = . ;
+ _data = . ;
+ *(.data)
+ *(.data*)
+ *(.RAMtext)
+ . = ALIGN(4);
+ _edata = . ;
+ } >RAM
+
+ /* Uninitialized data */
+ .bss (NOLOAD) :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+ __bss_start__ = .;
+ _bss = .;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* Pointers to end of data for dynamic memory management */
+ PROVIDE (end = _ebss);
+ PROVIDE (_end = _ebss);
+
+ /* Remove debugging from standard libraries */
+ /DISCARD/ :
+ {
+ libc.a (*)
+ libm.a (*)
+ libgcc.a (*)
+ }
+}
diff --git a/src/stm32f0/stm32f0xx_hal_conf.h b/src/stm32f0/stm32f0xx_hal_conf.h
new file mode 100644
index 00000000..fdc58be4
--- /dev/null
+++ b/src/stm32f0/stm32f0xx_hal_conf.h
@@ -0,0 +1,336 @@
+/**
+******************************************************************************
+* @file stm32f0xx_hal_conf.h
+* @brief HAL configuration file.
+******************************************************************************
+* @attention
+*
+* <h2><center>&copy; COPYRIGHT(c) 2019 STMicroelectronics</center></h2>
+*
+*Redistribution 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.
+*
+******************************************************************************
+*/
+
+/* Define to prevent recursive inclusion -----------------------------------*/
+#ifndef __STM32F0xx_HAL_CONF_H
+#define __STM32F0xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ----------------------------------------------------------*/
+/* Exported constants ------------------------------------------------------*/
+
+/* ########################## Module Selection ############################ */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+/*#define HAL_CRYP_MODULE_ENABLED */
+#define HAL_CAN_MODULE_ENABLED
+/*#define HAL_CEC_MODULE_ENABLED */
+/*#define HAL_COMP_MODULE_ENABLED */
+/*#define HAL_CRC_MODULE_ENABLED */
+/*#define HAL_CRYP_MODULE_ENABLED */
+/*#define HAL_TSC_MODULE_ENABLED */
+/*#define HAL_DAC_MODULE_ENABLED */
+/*#define HAL_I2S_MODULE_ENABLED */
+#define HAL_IWDG_MODULE_ENABLED
+/*#define HAL_LCD_MODULE_ENABLED */
+/*#define HAL_LPTIM_MODULE_ENABLED */
+/*#define HAL_RNG_MODULE_ENABLED */
+/*#define HAL_RTC_MODULE_ENABLED */
+/*#define HAL_SPI_MODULE_ENABLED */
+#define HAL_TIM_MODULE_ENABLED
+#define HAL_UART_MODULE_ENABLED
+/*#define HAL_USART_MODULE_ENABLED */
+/*#define HAL_IRDA_MODULE_ENABLED */
+/*#define HAL_SMARTCARD_MODULE_ENABLED */
+/*#define HAL_SMBUS_MODULE_ENABLED */
+/*#define HAL_WWDG_MODULE_ENABLED */
+/*#define HAL_PCD_MODULE_ENABLED */
+/*#define HAL_EXTI_MODULE_ENABLED */
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+
+/* ########################## HSE/HSI Values adaptation ################### */
+/**
+* @brief Adjust the value of External High Speed oscillator (HSE) used\
+* in your application.
+* This value is used by the RCC HAL module to compute the system frequency
+* (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+ /*!< Value of the External oscillator in Hz */
+ #define HSE_VALUE ((uint32_t)8000000)
+#endif /* HSE_VALUE */
+
+/**
+ * @brief In the following line adjust the External High Speed oscillator\
+ * (HSE) Startup
+ * Timeout value
+ */
+#if !defined (HSE_STARTUP_TIMEOUT)
+ /*!< Time out for HSE start up, in ms */
+ #define HSE_STARTUP_TIMEOUT ((uint32_t)100)
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+ /*!< Value of the Internal oscillator in Hz*/
+ #define HSI_VALUE ((uint32_t)8000000)
+#endif /* HSI_VALUE */
+
+/**
+ * @brief In the following line adjust the Internal High Speed oscillator \
+ * (HSI) Startup
+ * Timeout value
+ */
+#if !defined (HSI_STARTUP_TIMEOUT)
+ #define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI startup */
+#endif /* HSI_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator for ADC (HSI14) value.
+ */
+#if !defined (HSI14_VALUE)
+#define HSI14_VALUE ((uint32_t)14000000)
+ /*!< Value of the Internal High Speed oscillator for ADC in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI14_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator for USB (HSI48) value.
+ */
+#if !defined (HSI48_VALUE)
+#define HSI48_VALUE ((uint32_t)48000000)
+ /*!< Value of the Internal High Speed oscillator for USB in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI48_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSI_VALUE)
+ #define LSI_VALUE ((uint32_t)40000)
+#endif /* LSI_VALUE */
+ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+/**
+ * @brief External Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSE_VALUE)
+ /*!< Value of the External Low Speed oscillator in Hz */
+ #define LSE_VALUE ((uint32_t)32768)
+#endif /* LSE_VALUE */
+
+#if !defined (LSE_STARTUP_TIMEOUT)
+ /*!< Time out for LSE start up, in ms */
+ #define LSE_STARTUP_TIMEOUT ((uint32_t)5000)
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ######################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
+/*!< tick interrupt priority (lowest by default) */
+#define TICK_INT_PRIORITY ((uint32_t)0)
+ /* Warning: Must be set to higher priority for HAL_Delay() */
+ /* and HAL_GetTick() usage under interrupt context */
+#define USE_RTOS 0
+#define PREFETCH_ENABLE 1
+#define INSTRUCTION_CACHE_ENABLE 0
+#define DATA_CACHE_ENABLE 0
+/* ########################## Assert Selection ############################# */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* ################## SPI peripheral configuration ######################### */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+* Activated: CRC code is present inside driver
+* Deactivated: CRC code cleaned from driver
+*/
+
+#define USE_SPI_CRC 0U
+
+/* Includes -----------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+ #include "stm32f0xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32f0xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32f0xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32f0xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32f0xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_CAN_MODULE_ENABLED
+ #include "stm32f0xx_hal_can.h"
+#endif /* HAL_CAN_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32f0xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+ #include "stm32f0xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32f0xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+ #include "stm32f0xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32f0xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32f0xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32f0xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32f0xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32f0xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32f0xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32f0xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32f0xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_TSC_MODULE_ENABLED
+ #include "stm32f0xx_hal_tsc.h"
+#endif /* HAL_TSC_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32f0xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32f0xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+/* Exported macro -----------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) \
+ ((expr) ? (void)0U : assert_failed((char *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------ */
+ void assert_failed(char* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_CONF_H */
+
+/********************** (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32f0/timer.c b/src/stm32f0/timer.c
new file mode 100644
index 00000000..e5628f93
--- /dev/null
+++ b/src/stm32f0/timer.c
@@ -0,0 +1,156 @@
+/*
+ * Timer and PWM functions for STM32F042 boards.
+ * Also replacement for 'generic/armcm_timer.c', which not compatible
+ * with Cortex-M0 CPUs
+ *
+ * Copyright (C) 2019 Eug Krashtan <eug.krashtan@gmail.com>
+ * This file may be distributed under the terms of the GNU GPLv3 license.
+ *
+ * DO NOT USE HAL! (Timer HAL extremely fat)
+ */
+
+#include "autoconf.h" // CONFIG_CLOCK_FREQ
+#include "board/internal.h" // SysTick
+#include "board/irq.h" // irq_disable
+#include "stm32f0xx.h"
+#include "log.h"
+#include "sched.h" // DECL_INIT
+#include "command.h" // shutdown
+
+DECL_CONSTANT("CLOCK_FREQ", CONFIG_CLOCK_FREQ);
+
+// Return the number of clock ticks for a given number of microseconds
+uint32_t
+timer_from_us(uint32_t us)
+{
+ return us * (CONFIG_CLOCK_FREQ / 1000000);
+}
+
+// Return true if time1 is before time2. Always use this function to
+// compare times as regular C comparisons can fail if the counter
+// rolls over.
+uint8_t
+timer_is_before(uint32_t time1, uint32_t time2)
+{
+ return (int32_t)(time1 - time2) < 0;
+}
+
+// Set the next irq time
+static void
+timer_set_diff(uint32_t value)
+{
+ SysTick->LOAD = value;
+ SysTick->VAL = 0;
+ SysTick->LOAD = 0;
+}
+
+// Activate timer dispatch as soon as possible
+void
+timer_kick(void)
+{
+ SysTick->LOAD = 0;
+ SysTick->VAL = 0;
+ SCB->ICSR = SCB_ICSR_PENDSTSET_Msk;
+}
+
+/*
+ * TIM2 (32bit) used instead of DWT->CYCCNT in original variant
+ */
+void TimerInit(void)
+{
+ RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
+
+ TIM2->PSC = 0;
+ //TIM2->ARR = 0xFFFFFFFF; reset value
+ TIM2->DIER = TIM_DIER_UIE;
+ TIM2->CR1 = TIM_CR1_CEN;
+
+ NVIC_EnableIRQ(TIM2_IRQn);
+
+ // Enable SysTick
+ irqstatus_t flag = irq_save();
+ NVIC_SetPriority(SysTick_IRQn, 2);
+ SysTick->CTRL = (SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_TICKINT_Msk
+ | SysTick_CTRL_ENABLE_Msk);
+ timer_kick();
+ irq_restore(flag);
+
+}
+DECL_INIT(TimerInit);
+
+uint32_t
+timer_read_time(void)
+{
+ return TIM2->CNT;
+}
+
+static uint32_t timer_repeat_until;
+#define TIMER_IDLE_REPEAT_TICKS timer_from_us(500)
+#define TIMER_REPEAT_TICKS timer_from_us(100)
+
+#define TIMER_MIN_TRY_TICKS timer_from_us(2)
+#define TIMER_DEFER_REPEAT_TICKS timer_from_us(5)
+
+// Invoke timers
+static uint32_t
+timer_dispatch_many(void)
+{
+ uint32_t tru = timer_repeat_until;
+ for (;;) {
+ // Run the next software timer
+ uint32_t next = sched_timer_dispatch();
+
+ uint32_t now = timer_read_time();
+ int32_t diff = next - now;
+ if (diff > (int32_t)TIMER_MIN_TRY_TICKS)
+ // Schedule next timer normally.
+ return diff;
+
+ if (unlikely(timer_is_before(tru, now))) {
+ // Check if there are too many repeat timers
+ if (diff < (int32_t)(-timer_from_us(1000)))
+ try_shutdown("Rescheduled timer in the past");
+ if (sched_tasks_busy()) {
+ timer_repeat_until = now + TIMER_REPEAT_TICKS;
+ return TIMER_DEFER_REPEAT_TICKS;
+ }
+ timer_repeat_until = tru = now + TIMER_IDLE_REPEAT_TICKS;
+ }
+
+ // Next timer in the past or near future - wait for it to be ready
+ irq_enable();
+ while (unlikely(diff > 0))
+ diff = next - timer_read_time();
+ irq_disable();
+ }
+}
+
+// IRQ handler
+void __visible __aligned(16) // aligning helps stabilize perf benchmarks
+SysTick_Handler(void)
+{
+ irq_disable();
+ uint32_t diff = timer_dispatch_many();
+ timer_set_diff(diff);
+ irq_enable();
+}
+
+// Make sure timer_repeat_until doesn't wrap 32bit comparisons
+void
+timer_task(void)
+{
+ uint32_t now = timer_read_time();
+ irq_disable();
+ if (timer_is_before(timer_repeat_until, now))
+ timer_repeat_until = now;
+ irq_enable();
+}
+DECL_TASK(timer_task);
+
+
+void TIM2_IRQHandler(void)
+{
+ if(TIM2->SR & TIM_SR_UIF) {
+ TIM2->SR &= ~TIM_SR_UIF; // clear UIF flag
+ }
+}