diff --git a/MySensors.h b/MySensors.h
index de78f3688..0dbc4b064 100644
--- a/MySensors.h
+++ b/MySensors.h
@@ -70,6 +70,9 @@
 #elif defined(ARDUINO_ARCH_STM32F1)
 #include "hal/architecture/STM32F1/MyHwSTM32F1.cpp"
 #include "hal/crypto/generic/MyCryptoGeneric.cpp"
+#elif defined(ARDUINO_ARCH_STM32)
+#include "hal/architecture/STM32/MyHwSTM32.cpp"
+#include "hal/crypto/generic/MyCryptoGeneric.cpp"
 #elif defined(ARDUINO_ARCH_NRF5) || defined(ARDUINO_ARCH_NRF52)
 #include "hal/architecture/NRF5/MyHwNRF5.cpp"
 #include "hal/crypto/generic/MyCryptoGeneric.cpp"
@@ -313,7 +316,7 @@ MY_DEFAULT_RX_LED_PIN in your sketch instead to enable LEDs
 // RAM ROUTING TABLE
 #if defined(MY_RAM_ROUTING_TABLE_FEATURE) && defined(MY_REPEATER_FEATURE)
 // activate feature based on architecture
-#if defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_NRF5) || defined(ARDUINO_ARCH_STM32F1) || defined(TEENSYDUINO) || defined(__linux__)
+#if defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_NRF5) || defined(ARDUINO_ARCH_STM32) || defined(ARDUINO_ARCH_STM32F1) || defined(TEENSYDUINO) || defined(__linux__)
 #define MY_RAM_ROUTING_TABLE_ENABLED
 #elif defined(ARDUINO_ARCH_AVR)
 #if defined(__avr_atmega1280__) || defined(__avr_atmega1284__) || defined(__avr_atmega2560__)
@@ -447,6 +450,8 @@ MY_DEFAULT_RX_LED_PIN in your sketch instead to enable LEDs
 #include "hal/architecture/Linux/MyMainLinuxGeneric.cpp"
 #elif defined(ARDUINO_ARCH_STM32F1)
 #include "hal/architecture/STM32F1/MyMainSTM32F1.cpp"
+#elif defined(ARDUINO_ARCH_STM32)
+#include "hal/architecture/STM32/MyMainSTM32.cpp"
 #elif defined(__arm__) && defined(TEENSYDUINO)
 #include "hal/architecture/Teensy3/MyMainTeensy3.cpp"
 #endif
diff --git a/hal/architecture/STM32/MyHwSTM32.cpp b/hal/architecture/STM32/MyHwSTM32.cpp
new file mode 100644
index 000000000..712d409ab
--- /dev/null
+++ b/hal/architecture/STM32/MyHwSTM32.cpp
@@ -0,0 +1,203 @@
+/*
+ * The MySensors Arduino library handles the wireless radio link and protocol
+ * between your home built sensors/actuators and HA controller of choice.
+ * The sensors forms a self healing radio network with optional repeaters. Each
+ * repeater and gateway builds a routing tables in EEPROM which keeps track of the
+ * network topology allowing messages to be routed to nodes.
+ *
+ * Created by Henrik Ekblad <henrik.ekblad@mysensors.org>
+ * Copyright (C) 2013-2020 Sensnology AB
+ * Full contributor list: https://github.com/mysensors/MySensors/graphs/contributors
+ *
+ * Documentation: http://www.mysensors.org
+ * Support Forum: http://forum.mysensors.org
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * Arduino core for STM32: https://github.com/stm32duino/Arduino_Core_STM32
+ *
+ * MySensors Arduino Core STM32 implementation, Copyright (C) 2019-2020 Olivier Mauti <olivier@mysensors.org>
+ */
+
+#include "MyHwSTM32.h"
+
+/*
+* Pinout STM32F103C8 dev board:
+* http://wiki.stm32duino.com/images/a/ae/Bluepillpinout.gif
+*
+* Wiring RFM69 radio / SPI1
+* --------------------------------------------------
+* CLK	PA5
+* MISO	PA6
+* MOSI	PA7
+* CSN	PA4
+* CE	NA
+* IRQ	PA3 (default)
+*
+* Wiring RF24 radio / SPI1
+* --------------------------------------------------
+* CLK	PA5
+* MISO	PA6
+* MOSI	PA7
+* CSN	PA4
+* CE	PB0 (default)
+* IRQ	NA
+*
+*/
+bool hwInit(void)
+{
+#if !defined(MY_DISABLED_SERIAL)
+	MY_SERIALDEVICE.begin(MY_BAUD_RATE);
+#if defined(MY_GATEWAY_SERIAL)
+	while (!MY_SERIALDEVICE) {}
+#endif
+#endif
+	return true;
+}
+
+void hwReadConfigBlock(void *buf, void *addr, size_t length)
+{
+	uint8_t *dst = static_cast<uint8_t *>(buf);
+	int pos = reinterpret_cast<int>(addr);
+	while (length-- > 0) {
+		*dst++ = EEPROM.read(pos++);
+	}
+}
+
+void hwWriteConfigBlock(void *buf, void *addr, size_t length)
+{
+	uint8_t *src = static_cast<uint8_t *>(buf);
+	int pos = reinterpret_cast<int>(addr);
+	while (length-- > 0) {
+		EEPROM.write(pos++, *src++);
+	}
+}
+
+uint8_t hwReadConfig(const int addr)
+{
+	uint8_t value;
+	hwReadConfigBlock(&value, reinterpret_cast<void *>(addr), 1);
+	return value;
+}
+
+void hwWriteConfig(const int addr, uint8_t value)
+{
+	hwWriteConfigBlock(&value, reinterpret_cast<void *>(addr), 1);
+}
+
+int8_t hwSleep(uint32_t ms)
+{
+	// TODO: Not supported!
+	(void)ms;
+	return MY_SLEEP_NOT_POSSIBLE;
+}
+
+int8_t hwSleep(const uint8_t interrupt, const uint8_t mode, uint32_t ms)
+{
+	// TODO: Not supported!
+	(void)interrupt;
+	(void)mode;
+	(void)ms;
+	return MY_SLEEP_NOT_POSSIBLE;
+}
+
+int8_t hwSleep(const uint8_t interrupt1, const uint8_t mode1, const uint8_t interrupt2,
+               const uint8_t mode2,
+               uint32_t ms)
+{
+	// TODO: Not supported!
+	(void)interrupt1;
+	(void)mode1;
+	(void)interrupt2;
+	(void)mode2;
+	(void)ms;
+	return MY_SLEEP_NOT_POSSIBLE;
+}
+
+uint32_t hwGetSleepRemaining(void)
+{
+	// not implemented yet
+	return 0ul;
+}
+
+
+void hwRandomNumberInit(void)
+{
+	// use internal temperature sensor as noise source
+	/*
+	adc_reg_map *regs = ADC1->regs;
+	regs->CR2 |= ADC_CR2_TSVREFE;
+	regs->SMPR1 |= ADC_SMPR1_SMP16;
+
+	uint32_t seed = 0;
+	uint16_t currentValue = 0;
+	uint16_t newValue = 0;
+
+	for (uint8_t i = 0; i < 32; i++) {
+		const uint32_t timeout = hwMillis() + 20;
+		while (timeout >= hwMillis()) {
+			newValue = adc_read(ADC1, 16);
+			if (newValue != currentValue) {
+				currentValue = newValue;
+				break;
+			}
+		}
+		seed ^= ( (newValue + hwMillis()) & 7) << i;
+	}
+	randomSeed(seed);
+	regs->CR2 &= ~ADC_CR2_TSVREFE; // disable VREFINT and temp sensor
+	*/
+}
+
+bool hwUniqueID(unique_id_t *uniqueID)
+{
+	(void)memcpy((uint8_t *)uniqueID, (uint32_t *)0x1FFFF7E0, 16); // FlashID + ChipID
+	return true;
+}
+
+uint16_t hwCPUVoltage(void)
+{
+	/*
+	adc_reg_map *regs = ADC1->regs;
+	regs->CR2 |= ADC_CR2_TSVREFE; // enable VREFINT and temp sensor
+	regs->SMPR1 =  ADC_SMPR1_SMP17; // sample rate for VREFINT ADC channel
+	adc_calibrate(ADC1);
+
+	const uint16_t vdd = adc_read(ADC1, 17);
+	regs->CR2 &= ~ADC_CR2_TSVREFE; // disable VREFINT and temp sensor
+	return 1200 * 4096 / vdd;
+	*/
+	return 0;
+}
+
+uint16_t hwCPUFrequency(void)
+{
+	return F_CPU/100000UL;
+}
+
+int8_t hwCPUTemperature(void)
+{
+	/*
+	adc_reg_map *regs = ADC1->regs;
+	regs->CR2 |= ADC_CR2_TSVREFE; // enable VREFINT and Temperature sensor
+	regs->SMPR1 |= ADC_SMPR1_SMP16 | ADC_SMPR1_SMP17;
+	adc_calibrate(ADC1);
+
+	//const uint16_t adc_temp = adc_read(ADC1, 16);
+	//const uint16_t vref = 1200 * 4096 / adc_read(ADC1, 17);
+	// calibrated at 25°C, ADC output = 1430mV, avg slope = 4.3mV / °C, increasing temp ~ lower voltage
+	const int8_t temp = static_cast<int8_t>((1430.0 - (adc_read(ADC1, 16) * 1200 / adc_read(ADC1,
+	                                        17))) / 4.3 + 25.0);
+	regs->CR2 &= ~ADC_CR2_TSVREFE; // disable VREFINT and temp sensor
+	return (temp - MY_STM32_TEMPERATURE_OFFSET) / MY_STM32_TEMPERATURE_GAIN;
+	*/
+	return 0;
+}
+
+uint16_t hwFreeMem(void)
+{
+	//Not yet implemented
+	return FUNCTION_NOT_SUPPORTED;
+}
diff --git a/hal/architecture/STM32/MyHwSTM32.h b/hal/architecture/STM32/MyHwSTM32.h
new file mode 100644
index 000000000..aae0b49a0
--- /dev/null
+++ b/hal/architecture/STM32/MyHwSTM32.h
@@ -0,0 +1,91 @@
+/*
+ * The MySensors Arduino library handles the wireless radio link and protocol
+ * between your home built sensors/actuators and HA controller of choice.
+ * The sensors forms a self healing radio network with optional repeaters. Each
+ * repeater and gateway builds a routing tables in EEPROM which keeps track of the
+ * network topology allowing messages to be routed to nodes.
+ *
+ * Created by Henrik Ekblad <henrik.ekblad@mysensors.org>
+ * Copyright (C) 2013-2020 Sensnology AB
+ * Full contributor list: https://github.com/mysensors/MySensors/graphs/contributors
+ *
+ * Documentation: http://www.mysensors.org
+ * Support Forum: http://forum.mysensors.org
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * Arduino core for STM32: https://github.com/stm32duino/Arduino_Core_STM32
+ *
+ * MySensors Arduino Core STM32 implementation, Copyright (C) 2019-2020 Olivier Mauti <olivier@mysensors.org>
+ */
+
+#ifndef MyHwSTM32_h
+#define MyHwSTM32_h
+
+#include <EEPROM.h>
+#include <IWatchdog.h>
+#include <SPI.h>
+
+#ifdef __cplusplus
+#include <Arduino.h>
+#endif
+
+#define CRYPTO_LITTLE_ENDIAN
+
+#ifndef MY_SERIALDEVICE
+#define MY_SERIALDEVICE Serial
+#endif
+
+#ifndef MY_DEBUGDEVICE
+#define MY_DEBUGDEVICE MY_SERIALDEVICE
+#endif
+
+#ifndef MY_STM32_TEMPERATURE_OFFSET
+#define MY_STM32_TEMPERATURE_OFFSET (0.0f)
+#endif
+
+#ifndef MY_STM32_TEMPERATURE_GAIN
+#define MY_STM32_TEMPERATURE_GAIN (1.0f)
+#endif
+
+// SS default
+#ifndef SS
+#define SS PA4
+#endif
+
+// mapping
+#define yield()				  // not defined
+
+#ifndef digitalPinToInterrupt
+#define digitalPinToInterrupt(__pin) (__pin)
+#endif
+
+#define hwDigitalWrite(__pin, __value) digitalWrite(__pin, __value)
+#define hwDigitalRead(__pin) digitalRead(__pin)
+#define hwPinMode(__pin, __value) pinMode(__pin, __value)
+#define hwWatchdogReset() IWatchdog.reload()
+#define hwReboot() IWatchdog.begin(125)
+#define hwMillis() millis()
+
+extern void serialEventRun(void) __attribute__((weak));
+bool hwInit(void);
+void hwRandomNumberInit(void);
+void hwReadConfigBlock(void *buf, void *addr, size_t length);
+void hwWriteConfigBlock(void *buf, void *addr, size_t length);
+void hwWriteConfig(const int addr, uint8_t value);
+uint8_t hwReadConfig(const int addr);
+
+// SOFTSPI
+#ifdef MY_SOFTSPI
+#error Soft SPI is not available on this architecture!
+#endif
+#define hwSPI SPI //!< hwSPI
+
+
+#ifndef DOXYGEN
+#define MY_CRITICAL_SECTION
+#endif  /* DOXYGEN */
+
+#endif
diff --git a/hal/architecture/STM32/MyMainSTM32.cpp b/hal/architecture/STM32/MyMainSTM32.cpp
new file mode 100644
index 000000000..37a9f1dc5
--- /dev/null
+++ b/hal/architecture/STM32/MyMainSTM32.cpp
@@ -0,0 +1,75 @@
+/*
+ * The MySensors Arduino library handles the wireless radio link and protocol
+ * between your home built sensors/actuators and HA controller of choice.
+ * The sensors forms a self healing radio network with optional repeaters. Each
+ * repeater and gateway builds a routing tables in EEPROM which keeps track of the
+ * network topology allowing messages to be routed to nodes.
+ *
+ * Created by Henrik Ekblad <henrik.ekblad@mysensors.org>
+ * Copyright (C) 2013-2020 Sensnology AB
+ * Full contributor list: https://github.com/mysensors/MySensors/graphs/contributors
+ *
+ * Documentation: http://www.mysensors.org
+ * Support Forum: http://forum.mysensors.org
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * Arduino core for STM32: https://github.com/stm32duino/Arduino_Core_STM32
+ *
+ * MySensors Arduino Core STM32 implementation, Copyright (C) 2019-2020 Olivier Mauti <olivier@mysensors.org>
+ */
+
+#define ARDUINO_MAIN
+#include "Arduino.h"
+
+// Weak empty variant initialization function.
+// May be redefined by variant files.
+void initVariant() __attribute__((weak));
+void initVariant() { }
+
+// Force init to be called *first*, i.e. before static object allocation.
+// Otherwise, statically allocated objects that need HAL may fail.
+__attribute__((constructor(101))) void premain()
+{
+
+	// Required by FreeRTOS, see http://www.freertos.org/RTOS-Cortex-M3-M4.html
+#ifdef NVIC_PRIORITYGROUP_4
+	HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
+#endif
+#if (__CORTEX_M == 0x07U)
+	// Defined in CMSIS core_cm7.h
+#ifndef I_CACHE_DISABLED
+	SCB_EnableICache();
+#endif
+#ifndef D_CACHE_DISABLED
+	SCB_EnableDCache();
+#endif
+#endif
+
+	init();
+}
+
+/*
+ * \brief Main entry point of Arduino application
+ */
+int main(void)
+{
+	initVariant();
+
+	_begin(); // Startup MySensors library
+
+	for (;;) {
+#if defined(CORE_CALLBACK)
+		CoreCallback();
+#endif
+		_process();	// Process incoming data
+		loop();
+		if (serialEventRun) {
+			serialEventRun();
+		}
+	}
+
+	return 0;
+}