aboutsummaryrefslogtreecommitdiff
path: root/stm32f091
diff options
context:
space:
mode:
Diffstat (limited to 'stm32f091')
-rw-r--r--stm32f091/Si7021_driver_STM32.patch25
m---------stm32f091/lib/Si7021_driver_STM320
-rw-r--r--stm32f091/main.c33
-rw-r--r--stm32f091/main.h12
-rw-r--r--stm32f091/makefile38
-rw-r--r--stm32f091/sensor.c37
-rw-r--r--stm32f091/sensor.h20
-rw-r--r--stm32f091/setup.c106
-rw-r--r--stm32f091/setup.h7
-rw-r--r--stm32f091/stm32f0xx_hal_conf.h117
-rw-r--r--stm32f091/stm32f0xx_hal_msp.c32
-rw-r--r--stm32f091/stm32f0xx_hal_msp.h9
12 files changed, 405 insertions, 31 deletions
diff --git a/stm32f091/Si7021_driver_STM32.patch b/stm32f091/Si7021_driver_STM32.patch
new file mode 100644
index 0000000..eff7623
--- /dev/null
+++ b/stm32f091/Si7021_driver_STM32.patch
@@ -0,0 +1,25 @@
+diff --git a/driver/inc/Si7021_driver.h b/driver/inc/Si7021_driver.h
+index 7ed1f4a..50803ef 100644
+--- a/driver/inc/Si7021_driver.h
++++ b/driver/inc/Si7021_driver.h
+@@ -1,7 +1,7 @@
+ #ifndef SI7021_H_
+ #define SI7021_H_
+
+-#include "stm32f4xx_hal.h"
++#include "stm32f0xx_hal.h"
+
+ #define RES0 0
+ #define RES1 7
+diff --git a/driver/src/Si7021_driver.c b/driver/src/Si7021_driver.c
+index 47df31c..d11ee38 100644
+--- a/driver/src/Si7021_driver.c
++++ b/driver/src/Si7021_driver.c
+@@ -1,5 +1,6 @@
+ #include <Si7021_driver.h>
+-#include <i2c.h>
++#include "stm32f0xx_hal_i2c.h"
++#include "main.h"
+
+ static const uint16_t I2C_ADDR = (0x40<<1); // Si7021 I2C address
+ static const uint8_t HEATER_CURRENT_OFFSET = 3; // current value in mA for register value 0
diff --git a/stm32f091/lib/Si7021_driver_STM32 b/stm32f091/lib/Si7021_driver_STM32
new file mode 160000
+Subproject cae65b26c416b7ebe870d0b16886e74b3a652af
diff --git a/stm32f091/main.c b/stm32f091/main.c
index 848bfac..68e8dd4 100644
--- a/stm32f091/main.c
+++ b/stm32f091/main.c
@@ -1,29 +1,22 @@
#include <FreeRTOS.h>
#include <task.h>
-#include <stm32f0xx.h>
-#include <stdint.h>
+#include <stm32f0xx_hal.h>
-#define PORT GPIOA
-#define PIN 5
+#include "main.h"
+#include "setup.h"
+#include "sensor.h"
-void task_1() {
- uint8_t led = 1;
-
- while (1) {
- PORT->ODR &= ~(1 << PIN);
- PORT->ODR |= (led << PIN);
- led ^= 1;
-
- vTaskDelay(1000 / portTICK_RATE_MS);
- }
-}
+I2C_HandleTypeDef hi2c2;
+UART_HandleTypeDef huart2;
int main() {
- RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN;
+ HAL_Init();
+
+ SystemClock_Config();
+ MX_GPIO_Init();
+ MX_USART2_UART_Init();
+ MX_I2C2_Init();
- PORT->MODER &= ~(0b11 << (PIN * 2));
- PORT->MODER |= (0b01 << (PIN * 2));
-
- xTaskCreate(task_1, "task1", 128, NULL, 1, NULL);
+ xTaskCreate(ws_sensor_read_task, "sensor", 128, NULL, 1, NULL);
vTaskStartScheduler();
}
diff --git a/stm32f091/main.h b/stm32f091/main.h
new file mode 100644
index 0000000..7c13733
--- /dev/null
+++ b/stm32f091/main.h
@@ -0,0 +1,12 @@
+#pragma once
+
+#include <stm32f0xx_hal_i2c.h>
+#include <stm32f0xx_hal_uart.h>
+
+#define hi2c1 hi2c2
+
+extern I2C_HandleTypeDef hi2c2;
+extern UART_HandleTypeDef huart2;
+
+void task_1();
+int main();
diff --git a/stm32f091/makefile b/stm32f091/makefile
index a359853..ffcb109 100644
--- a/stm32f091/makefile
+++ b/stm32f091/makefile
@@ -6,26 +6,28 @@ RM = rm -f
TARGET = main
SHARED_FLAGS += -g
-SHARED_FLAGS += -D STM32F091xC
+SHARED_FLAGS += -DSTM32F091xC
SHARED_FLAGS += -Wall
SHARED_FLAGS += -Wextra
# SHARED_FLAGS += -Wno-register
SHARED_FLAGS += -Wa,--defsym,CALL_ARM_SYSTEM_INIT=1
# SHARED_FLAGS += -I/usr/arm-none-eabi/include/
+SHARED_FLAGS += -I./lib/STM32-base-STM32Cube/HAL/STM32F0xx/inc
+SHARED_FLAGS += -I./lib/STM32-base-STM32Cube/HAL/STM32F0xx/inc/Legacy
SHARED_FLAGS += -I./lib/STM32-base-STM32Cube/CMSIS/ARM/inc
SHARED_FLAGS += -I./lib/STM32-base-STM32Cube/CMSIS/STM32F0xx/inc
SHARED_FLAGS += -I./lib/STM32-base/startup
SHARED_FLAGS += -I./lib/FreeRTOS-Kernel/include
SHARED_FLAGS += -I./lib/FreeRTOS-Kernel/portable/GCC/ARM_CM0/
+SHARED_FLAGS += -I./lib/Si7021_driver_STM32/driver/inc/
SHARED_FLAGS += -I.
+SHARED_FLAGS += -O1
SHARED_FLAGS += -ffunction-sections
SHARED_FLAGS += -fdata-sections
+SHARED_FLAGS += -Wl,--gc-sections
SHARED_FLAGS += -mlittle-endian
SHARED_FLAGS += -mthumb
-# SHARED_FLAGS += -masm-syntax-unified
SHARED_FLAGS += -specs=nosys.specs
-# SHARED_FLAGS += -fno-threadsafe-statics
-# SHARED_FLAGS += -fno-rtti
SHARED_FLAGS += -fno-exceptions
SHARED_FLAGS += -fno-unwind-tables
SHARED_FLAGS += -Wl,-L./lib/STM32-base/linker,-T./lib/STM32-base/linker/STM32F0xx/STM32F091xC.ld
@@ -37,6 +39,8 @@ LFLAGS += $(SHARED_FLAGS)
AFLAGS += $(SHARED_FLAGS)
OBJS += $(patsubst %.c,%.o, $(wildcard *.c))
+OBJS += ./lib/STM32-base/startup/STM32F0xx/STM32F091xC.o
+OBJS += ./lib/STM32-base-STM32Cube/CMSIS/STM32F0xx/src/system_stm32f0xx.o
OBJS += lib/FreeRTOS-Kernel/croutine.o \
lib/FreeRTOS-Kernel/event_groups.o \
lib/FreeRTOS-Kernel/list.o \
@@ -46,9 +50,23 @@ OBJS += lib/FreeRTOS-Kernel/croutine.o \
lib/FreeRTOS-Kernel/timers.o \
lib/FreeRTOS-Kernel/portable/GCC/ARM_CM0/port.o \
lib/FreeRTOS-Kernel/portable/MemMang/heap_4.o
-
-OBJS += ./lib/STM32-base/startup/STM32F0xx/STM32F091xC.o
-OBJS += ./lib/STM32-base-STM32Cube/CMSIS/STM32F0xx/src/system_stm32f0xx.o
+OBJS += lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_rcc.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_rcc_ex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_i2c.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_i2c_ex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_gpio.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_dma.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_cortex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_pwr.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_pwr_ex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_flash.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_flash_ex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_tim.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_tim_ex.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_uart.o \
+ lib/STM32-base-STM32Cube/HAL/STM32F0xx/src/stm32f0xx_hal_uart_ex.o
+OBJS += lib/Si7021_driver_STM32/driver/src/Si7021_driver.o
.PHONY: flash clean
@@ -61,9 +79,6 @@ $(TARGET).bin: $(TARGET).elf
%.o: %.c
$(CC) -c $(CFLAGS) $< -o $@
-%.o: %.c
- $(CC) -c $(CFLAGS) $< -o $@
-
$(TARGET).elf: $(OBJS)
$(LD) $(LFLAGS) $^ -o $@
@@ -71,7 +86,8 @@ flash: $(TARGET).bin
st-flash write $(TARGET).bin 0x08000000
compile_commands: clean
- compiledb make
+ compiledb make -n
+ ../scripts/compiledb-full-path-mingw.sh compile_commands.json
clean:
$(RM) $(TARGET).bin $(TARGET).elf $(OBJS)
diff --git a/stm32f091/sensor.c b/stm32f091/sensor.c
new file mode 100644
index 0000000..f2e9e29
--- /dev/null
+++ b/stm32f091/sensor.c
@@ -0,0 +1,37 @@
+#include <FreeRTOS.h>
+#include <task.h>
+#include <Si7021_driver.h>
+
+#include "sensor.h"
+#include "backlog.h"
+
+uint8_t ws_sensor_temperature() {
+ float temp = 0.f;
+ r_single_Si7021(&temp, Temperature);
+ return (uint8_t) temp; //TODO: convert with range -> util.h
+}
+
+uint8_t ws_sensor_humidity() {
+ return 0x00;
+}
+
+uint8_t ws_sensor_atmospheric_pressure() {
+ return 0x00;
+}
+
+void ws_sensor_read() {
+ ws_s_backlog_record record = {
+ .sens_temperature = ws_sensor_temperature(),
+ .sens_atm_pressure = ws_sensor_atmospheric_pressure(),
+ .sens_humidity = ws_sensor_humidity()
+ };
+ ws_backlog_add_record(record);
+}
+
+void ws_sensor_read_task() {
+ while (1) {
+ ws_sensor_read();
+ vTaskDelay(portTICK_PERIOD_MS * 1000 * 60);
+ }
+}
+
diff --git a/stm32f091/sensor.h b/stm32f091/sensor.h
new file mode 100644
index 0000000..802656b
--- /dev/null
+++ b/stm32f091/sensor.h
@@ -0,0 +1,20 @@
+#pragma once
+
+#include <stdint.h>
+
+/** Get current temperature measurement */
+uint8_t ws_sensor_temperature();
+/** Get current humidity measurement */
+uint8_t ws_sensor_humidity();
+/** Get current atmospheric pressure measurement */
+uint8_t ws_sensor_atmospheric_pressure();
+
+/**
+ * Put measurements from every sensor into a `ws_s_backlog_record`, and commit
+ * that struct to the database
+ */
+void ws_sensor_read();
+
+/** FreeRTOS task that runs `ws_sensor_read` every minute */
+void ws_sensor_read_task();
+
diff --git a/stm32f091/setup.c b/stm32f091/setup.c
new file mode 100644
index 0000000..42f54b3
--- /dev/null
+++ b/stm32f091/setup.c
@@ -0,0 +1,106 @@
+#include <stm32f0xx_hal.h>
+#include <stm32f0xx_hal_rcc.h>
+#include <stm32f0xx_hal_i2c.h>
+#include <stm32f0xx_hal_uart.h>
+
+#include "main.h"
+#include "setup.h"
+
+#define B1_Pin GPIO_PIN_13
+#define B1_GPIO_Port GPIOC
+#define USART_TX_Pin GPIO_PIN_2
+#define USART_TX_GPIO_Port GPIOA
+#define USART_RX_Pin GPIO_PIN_3
+#define USART_RX_GPIO_Port GPIOA
+#define LD2_Pin GPIO_PIN_5
+#define LD2_GPIO_Port GPIOA
+#define TMS_Pin GPIO_PIN_13
+#define TMS_GPIO_Port GPIOA
+#define TCK_Pin GPIO_PIN_14
+#define TCK_GPIO_Port GPIOA
+
+void SystemClock_Config() {
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+
+ // Initializes the RCC Oscillators according to the specified parameters in
+ // the RCC_OscInitTypeDef structure.
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+ RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL12;
+ RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV2;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) return Error_Handler();
+
+ // Initializes the CPU, AHB and APB buses clocks
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) return Error_Handler();
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2;
+ PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) return Error_Handler();
+}
+
+void MX_I2C2_Init() {
+ hi2c2.Instance = I2C2;
+ hi2c2.Init.Timing = 0x20303E5D;
+ hi2c2.Init.OwnAddress1 = 0;
+ hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
+ hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
+ hi2c2.Init.OwnAddress2 = 0;
+ hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
+ hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
+ hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
+ if (HAL_I2C_Init(&hi2c2) != HAL_OK) return Error_Handler();
+ if (HAL_I2CEx_ConfigAnalogFilter(&hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK) return Error_Handler();
+ if (HAL_I2CEx_ConfigDigitalFilter(&hi2c2, 0) != HAL_OK) return Error_Handler();
+}
+
+void MX_USART2_UART_Init() {
+ 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_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;
+ if (HAL_UART_Init(&huart2) != HAL_OK) return Error_Handler();
+}
+
+void MX_GPIO_Init() {
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+
+ HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_RESET);
+
+ GPIO_InitStruct.Pin = B1_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(B1_GPIO_Port, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = LD2_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(LD2_GPIO_Port, &GPIO_InitStruct);
+}
+
+void Error_Handler() {
+ __disable_irq();
+ for(;;);
+}
+
diff --git a/stm32f091/setup.h b/stm32f091/setup.h
new file mode 100644
index 0000000..36eb9af
--- /dev/null
+++ b/stm32f091/setup.h
@@ -0,0 +1,7 @@
+#pragma once
+
+void SystemClock_Config();
+void MX_I2C2_Init();
+void MX_USART2_UART_Init();
+void MX_GPIO_Init();
+void Error_Handler();
diff --git a/stm32f091/stm32f0xx_hal_conf.h b/stm32f091/stm32f0xx_hal_conf.h
new file mode 100644
index 0000000..fc27221
--- /dev/null
+++ b/stm32f091/stm32f0xx_hal_conf.h
@@ -0,0 +1,117 @@
+#pragma once
+
+#define HSE_VALUE ((uint32_t)8000000)
+#define HSE_STARTUP_TIMEOUT ((uint32_t)100)
+#define HSI_VALUE ((uint32_t)8000000)
+#define HSI_STARTUP_TIMEOUT ((uint32_t)5000)
+#define HSI14_VALUE ((uint32_t)14000000)
+#define HSI48_VALUE ((uint32_t)48000000)
+#define LSI_VALUE ((uint32_t)40000)
+#define LSE_VALUE ((uint32_t)32768)
+#define LSE_STARTUP_TIMEOUT ((uint32_t)5000)
+
+#define VDD_VALUE 3300U
+#define TICK_INT_PRIORITY ((uint32_t)(1U<<__NVIC_PRIO_BITS) - 1U)
+
+#define USE_RTOS 0U
+#define PREFETCH_ENABLE 1U
+#define INSTRUCTION_CACHE_ENABLE 0U
+#define DATA_CACHE_ENABLE 0U
+#define USE_SPI_CRC 0U
+
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+#define HAL_UART_MODULE_ENABLED
+
+#ifdef HAL_RCC_MODULE_ENABLED
+#include <stm32f0xx_hal_rcc.h>
+#endif
+#ifdef HAL_GPIO_MODULE_ENABLED
+#include <stm32f0xx_hal_gpio.h>
+#endif
+#ifdef HAL_DMA_MODULE_ENABLED
+#include <stm32f0xx_hal_dma.h>
+#endif
+#ifdef HAL_CORTEX_MODULE_ENABLED
+#include <stm32f0xx_hal_cortex.h>
+#endif
+#ifdef HAL_ADC_MODULE_ENABLED
+#include <stm32f0xx_hal_adc.h>
+#endif
+#ifdef HAL_CAN_MODULE_ENABLED
+#include <stm32f0xx_hal_can.h>
+#endif
+#ifdef HAL_CEC_MODULE_ENABLED
+#include <stm32f0xx_hal_cec.h>
+#endif
+#ifdef HAL_COMP_MODULE_ENABLED
+#include <stm32f0xx_hal_comp.h>
+#endif
+#ifdef HAL_CRC_MODULE_ENABLED
+#include <stm32f0xx_hal_crc.h>
+#endif
+#ifdef HAL_DAC_MODULE_ENABLED
+#include <stm32f0xx_hal_dac.h>
+#endif
+#ifdef HAL_FLASH_MODULE_ENABLED
+#include <stm32f0xx_hal_flash.h>
+#endif
+#ifdef HAL_I2C_MODULE_ENABLED
+#include <stm32f0xx_hal_i2c.h>
+#endif
+#ifdef HAL_I2S_MODULE_ENABLED
+#include <stm32f0xx_hal_i2s.h>
+#endif
+#ifdef HAL_IRDA_MODULE_ENABLED
+#include <stm32f0xx_hal_irda.h>
+#endif
+#ifdef HAL_IWDG_MODULE_ENABLED
+#include <stm32f0xx_hal_iwdg.h>
+#endif
+#ifdef HAL_PCD_MODULE_ENABLED
+#include <stm32f0xx_hal_pcd.h>
+#endif
+#ifdef HAL_PWR_MODULE_ENABLED
+#include <stm32f0xx_hal_pwr.h>
+#endif
+#ifdef HAL_RTC_MODULE_ENABLED
+#include <stm32f0xx_hal_rtc.h>
+#endif
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+#include <stm32f0xx_hal_smartcard.h>
+#endif
+#ifdef HAL_SMBUS_MODULE_ENABLED
+#include <stm32f0xx_hal_smbus.h>
+#endif
+#ifdef HAL_SPI_MODULE_ENABLED
+#include <stm32f0xx_hal_spi.h>
+#endif
+#ifdef HAL_TIM_MODULE_ENABLED
+#include <stm32f0xx_hal_tim.h>
+#endif
+#ifdef HAL_TSC_MODULE_ENABLED
+#include <stm32f0xx_hal_tsc.h>
+#endif
+#ifdef HAL_UART_MODULE_ENABLED
+#include <stm32f0xx_hal_uart.h>
+#endif
+#ifdef HAL_USART_MODULE_ENABLED
+#include <stm32f0xx_hal_usart.h>
+#endif
+#ifdef HAL_WWDG_MODULE_ENABLED
+#include <stm32f0xx_hal_wwdg.h>
+#endif
+
+#ifdef USE_FULL_ASSERT
+#define assert_param(expr) ((expr) ? (void)0U : assert_failed((char *)__FILE__, __LINE__))
+void assert_failed(char* file, uint32_t line);
+#else
+#define assert_param(expr) ((void)0U)
+#endif
diff --git a/stm32f091/stm32f0xx_hal_msp.c b/stm32f091/stm32f0xx_hal_msp.c
new file mode 100644
index 0000000..8fd7330
--- /dev/null
+++ b/stm32f091/stm32f0xx_hal_msp.c
@@ -0,0 +1,32 @@
+#include "stm32f0xx_hal_msp.h"
+
+void HAL_MspInit(void) {
+ return;
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_NVIC_SetPriority(PendSV_IRQn, 3, 0);
+}
+
+void HAL_UART_MspInit(UART_HandleTypeDef* huart) {
+ return;
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(huart->Instance==USART2) {
+ __HAL_RCC_USART2_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ 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_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF1_USART2;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ }
+}
+
+void HAL_UART_MspDeInit(UART_HandleTypeDef* huart) {
+ return;
+ if(huart->Instance==USART2) {
+ __HAL_RCC_USART2_CLK_DISABLE();
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_2|GPIO_PIN_3);
+ }
+}
+
diff --git a/stm32f091/stm32f0xx_hal_msp.h b/stm32f091/stm32f0xx_hal_msp.h
new file mode 100644
index 0000000..3ffdf48
--- /dev/null
+++ b/stm32f091/stm32f0xx_hal_msp.h
@@ -0,0 +1,9 @@
+#pragma once
+
+#include <stm32f0xx_hal.h>
+#include <stm32f0xx_hal_uart.h>
+
+void HAL_MspInit(void);
+void HAL_UART_MspInit(UART_HandleTypeDef* huart);
+void HAL_UART_MspDeInit(UART_HandleTypeDef* huart);
+