diff --git a/miosix/_tools/testsuite/testsuite.cpp b/miosix/_tools/testsuite/testsuite.cpp
index 7a489fea1677765b6ce373c284e8da4f1f4a23fa..ce71b9421b1a6a3e247a195cfecdd4f3926f9846 100644
--- a/miosix/_tools/testsuite/testsuite.cpp
+++ b/miosix/_tools/testsuite/testsuite.cpp
@@ -1994,7 +1994,7 @@ void test_10()
     test_name("Exception handling");
     Thread::sleep(10);
     Thread *t=Thread::create(t10_p1,1024+512,0,NULL);
-    Thread::sleep(40);
+    Thread::sleep(80);
     if(Thread::exists(t)) fail("Thread not deleted");
     pass();
 }
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/core/stage_1_boot.cpp b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/core/stage_1_boot.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..1bcea824fce2ddbce9b2615cee40396d75cc517a
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/core/stage_1_boot.cpp
@@ -0,0 +1,269 @@
+
+#include "interfaces/arch_registers.h"
+#include "core/interrupts.h" //For the unexpected interrupt call
+#include "kernel/stage_2_boot.h"
+#include <string.h>
+
+/*
+ * startup.cpp
+ * STM32 C++ startup.
+ * Supports interrupt handlers in C++ without extern "C"
+ * Developed by Terraneo Federico, based on ST startup code.
+ * Additionally modified to boot Miosix.
+ */
+
+/**
+ * Called by Reset_Handler, performs initialization and calls main.
+ * Never returns.
+ */
+void program_startup() __attribute__((noreturn));
+void program_startup()
+{
+    //Cortex M3 core appears to get out of reset with interrupts already enabled
+    __disable_irq();
+
+    //These are defined in the linker script
+    extern unsigned char _etext asm("_etext");
+    extern unsigned char _data asm("_data");
+    extern unsigned char _edata asm("_edata");
+    extern unsigned char _bss_start asm("_bss_start");
+    extern unsigned char _bss_end asm("_bss_end");
+
+    //Initialize .data section, clear .bss section
+    unsigned char *etext=&_etext;
+    unsigned char *data=&_data;
+    unsigned char *edata=&_edata;
+    unsigned char *bss_start=&_bss_start;
+    unsigned char *bss_end=&_bss_end;
+    memcpy(data, etext, edata-data);
+    memset(bss_start, 0, bss_end-bss_start);
+
+    //Move on to stage 2
+    _init();
+
+    //If main returns, reboot
+    NVIC_SystemReset();
+    for(;;) ;
+}
+
+/**
+ * Reset handler, called by hardware immediately after reset
+ */
+void Reset_Handler() __attribute__((__interrupt__, noreturn));
+void Reset_Handler()
+{
+    /*
+     * SystemInit() is called *before* initializing .data and zeroing .bss
+     * Despite all startup files provided by ST do the opposite, there are three
+     * good reasons to do so:
+     * First, the CMSIS specifications say that SystemInit() must not access
+     * global variables, so it is actually possible to call it before
+     * Second, when running Miosix with the xram linker scripts .data and .bss
+     * are placed in the external RAM, so we *must* call SystemInit(), which
+     * enables xram, before touching .data and .bss
+     * Third, this is a performance improvement since the loops that initialize
+     * .data and zeros .bss now run with the CPU at full speed instead of 16MHz
+     * Note that it is called before switching stacks because the memory
+     * at _heap_end can be unavailable until the external RAM is initialized.
+     */
+    SystemInit();
+
+    /*
+     * Initialize process stack and switch to it.
+     * This is required for booting Miosix, a small portion of the top of the
+     * heap area will be used as stack until the first thread starts. After,
+     * this stack will be abandoned and the process stack will point to the
+     * current thread's stack.
+     */
+    asm volatile("ldr r0,  =_heap_end          \n\t"
+                 "msr psp, r0                  \n\t"
+                 "movw r0, #2                  \n\n" //Privileged, process stack
+                 "msr control, r0              \n\t"
+                 "isb                          \n\t":::"r0");
+
+    program_startup();
+}
+
+/**
+ * All unused interrupts call this function.
+ */
+extern "C" void Default_Handler() 
+{
+    unexpectedInterrupt();
+}
+
+//System handlers
+void /*__attribute__((weak))*/ Reset_Handler();     //These interrupts are not
+void /*__attribute__((weak))*/ NMI_Handler();       //weak because they are
+void /*__attribute__((weak))*/ HardFault_Handler(); //surely defined by Miosix
+void /*__attribute__((weak))*/ MemManage_Handler();
+void /*__attribute__((weak))*/ BusFault_Handler();
+void /*__attribute__((weak))*/ UsageFault_Handler();
+void /*__attribute__((weak))*/ SVC_Handler();
+void /*__attribute__((weak))*/ DebugMon_Handler();
+void /*__attribute__((weak))*/ PendSV_Handler();
+void /*__attribute__((weak))*/ SysTick_Handler();
+
+//Interrupt handlers
+void __attribute__((weak)) WWDG_IRQHandler();
+void __attribute__((weak)) PVD_IRQHandler();
+void __attribute__((weak)) TAMPER_IRQHandler();
+void __attribute__((weak)) RTC_IRQHandler();
+void __attribute__((weak)) FLASH_IRQHandler();
+void __attribute__((weak)) RCC_IRQHandler();
+void __attribute__((weak)) EXTI0_IRQHandler();
+void __attribute__((weak)) EXTI1_IRQHandler();
+void __attribute__((weak)) EXTI2_IRQHandler();
+void __attribute__((weak)) EXTI3_IRQHandler();
+void __attribute__((weak)) EXTI4_IRQHandler();
+void __attribute__((weak)) DMA1_Channel1_IRQHandler();
+void __attribute__((weak)) DMA1_Channel2_IRQHandler();
+void __attribute__((weak)) DMA1_Channel3_IRQHandler();
+void __attribute__((weak)) DMA1_Channel4_IRQHandler();
+void __attribute__((weak)) DMA1_Channel5_IRQHandler();
+void __attribute__((weak)) DMA1_Channel6_IRQHandler();
+void __attribute__((weak)) DMA1_Channel7_IRQHandler();
+void __attribute__((weak)) ADC1_2_IRQHandler();
+void __attribute__((weak)) USB_HP_CAN1_TX_IRQHandler();
+void __attribute__((weak)) USB_LP_CAN1_RX0_IRQHandler();
+void __attribute__((weak)) CAN1_RX1_IRQHandler();
+void __attribute__((weak)) CAN1_SCE_IRQHandler();
+void __attribute__((weak)) EXTI9_5_IRQHandler();
+void __attribute__((weak)) TIM1_BRK_IRQHandler();
+void __attribute__((weak)) TIM1_UP_IRQHandler();
+void __attribute__((weak)) TIM1_TRG_COM_IRQHandler();
+void __attribute__((weak)) TIM1_CC_IRQHandler();
+void __attribute__((weak)) TIM2_IRQHandler();
+void __attribute__((weak)) TIM3_IRQHandler();
+void __attribute__((weak)) TIM4_IRQHandler();
+void __attribute__((weak)) I2C1_EV_IRQHandler();
+void __attribute__((weak)) I2C1_ER_IRQHandler();
+void __attribute__((weak)) I2C2_EV_IRQHandler();
+void __attribute__((weak)) I2C2_ER_IRQHandler();
+void __attribute__((weak)) SPI1_IRQHandler();
+void __attribute__((weak)) SPI2_IRQHandler();
+void __attribute__((weak)) USART1_IRQHandler();
+void __attribute__((weak)) USART2_IRQHandler();
+void __attribute__((weak)) USART3_IRQHandler();
+void __attribute__((weak)) EXTI15_10_IRQHandler();
+void __attribute__((weak)) RTCAlarm_IRQHandler();
+void __attribute__((weak)) USBWakeUp_IRQHandler();
+
+//Stack top, defined in the linker script
+extern char _main_stack_top asm("_main_stack_top");
+
+//Interrupt vectors, must be placed @ address 0x00000000
+//The extern declaration is required otherwise g++ optimizes it out
+extern void (* const __Vectors[])();
+void (* const __Vectors[])() __attribute__ ((section(".isr_vector"))) =
+{       
+    reinterpret_cast<void (*)()>(&_main_stack_top),/* Stack pointer*/
+    Reset_Handler,              /* Reset Handler */
+    NMI_Handler,                /* NMI Handler */
+    HardFault_Handler,          /* Hard Fault Handler */
+    MemManage_Handler,          /* MPU Fault Handler */
+    BusFault_Handler,           /* Bus Fault Handler */
+    UsageFault_Handler,         /* Usage Fault Handler */
+    0,                          /* Reserved */
+    0,                          /* Reserved */
+    0,                          /* Reserved */
+    0,                          /* Reserved */
+    SVC_Handler,                /* SVCall Handler */
+    DebugMon_Handler,           /* Debug Monitor Handler */
+    0,                          /* Reserved */
+    PendSV_Handler,             /* PendSV Handler */
+    SysTick_Handler,            /* SysTick Handler */
+
+    /* External Interrupts */
+    WWDG_IRQHandler,
+    PVD_IRQHandler,
+    TAMPER_IRQHandler,
+    RTC_IRQHandler,
+    FLASH_IRQHandler,
+    RCC_IRQHandler,
+    EXTI0_IRQHandler,
+    EXTI1_IRQHandler,
+    EXTI2_IRQHandler,
+    EXTI3_IRQHandler,
+    EXTI4_IRQHandler,
+    DMA1_Channel1_IRQHandler,
+    DMA1_Channel2_IRQHandler,
+    DMA1_Channel3_IRQHandler,
+    DMA1_Channel4_IRQHandler,
+    DMA1_Channel5_IRQHandler,
+    DMA1_Channel6_IRQHandler,
+    DMA1_Channel7_IRQHandler,
+    ADC1_2_IRQHandler,
+    USB_HP_CAN1_TX_IRQHandler,
+    USB_LP_CAN1_RX0_IRQHandler,
+    CAN1_RX1_IRQHandler,
+    CAN1_SCE_IRQHandler,
+    EXTI9_5_IRQHandler,
+    TIM1_BRK_IRQHandler,
+    TIM1_UP_IRQHandler,
+    TIM1_TRG_COM_IRQHandler,
+    TIM1_CC_IRQHandler,
+    TIM2_IRQHandler,
+    TIM3_IRQHandler,
+    TIM4_IRQHandler,
+    I2C1_EV_IRQHandler,
+    I2C1_ER_IRQHandler,
+    I2C2_EV_IRQHandler,
+    I2C2_ER_IRQHandler,
+    SPI1_IRQHandler,
+    SPI2_IRQHandler,
+    USART1_IRQHandler,
+    USART2_IRQHandler,
+    USART3_IRQHandler,
+    EXTI15_10_IRQHandler,
+    RTCAlarm_IRQHandler,
+    USBWakeUp_IRQHandler,
+    0,0,0,0,0,0,0,
+    reinterpret_cast<void (*)()>(0xF108F85F)
+                                /* @0x108. This is for boot in RAM mode for
+                                   STM32F10x Medium Density devices. */
+};
+
+#pragma weak WWDG_IRQHandler = Default_Handler
+#pragma weak PVD_IRQHandler = Default_Handler
+#pragma weak TAMPER_IRQHandler = Default_Handler
+#pragma weak RTC_IRQHandler = Default_Handler
+#pragma weak FLASH_IRQHandler = Default_Handler
+#pragma weak RCC_IRQHandler = Default_Handler
+#pragma weak EXTI0_IRQHandler = Default_Handler
+#pragma weak EXTI1_IRQHandler = Default_Handler
+#pragma weak EXTI2_IRQHandler = Default_Handler
+#pragma weak EXTI3_IRQHandler = Default_Handler
+#pragma weak EXTI4_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel1_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel2_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel3_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel4_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel5_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel6_IRQHandler = Default_Handler
+#pragma weak DMA1_Channel7_IRQHandler = Default_Handler
+#pragma weak ADC1_2_IRQHandler = Default_Handler
+#pragma weak USB_HP_CAN1_TX_IRQHandler = Default_Handler
+#pragma weak USB_LP_CAN1_RX0_IRQHandler = Default_Handler
+#pragma weak CAN1_RX1_IRQHandler = Default_Handler
+#pragma weak CAN1_SCE_IRQHandler = Default_Handler
+#pragma weak EXTI9_5_IRQHandler = Default_Handler
+#pragma weak TIM1_BRK_IRQHandler = Default_Handler
+#pragma weak TIM1_UP_IRQHandler = Default_Handler
+#pragma weak TIM1_TRG_COM_IRQHandler = Default_Handler
+#pragma weak TIM1_CC_IRQHandler = Default_Handler
+#pragma weak TIM2_IRQHandler = Default_Handler
+#pragma weak TIM3_IRQHandler = Default_Handler
+#pragma weak TIM4_IRQHandler = Default_Handler
+#pragma weak I2C1_EV_IRQHandler = Default_Handler
+#pragma weak I2C1_ER_IRQHandler = Default_Handler
+#pragma weak I2C2_EV_IRQHandler = Default_Handler
+#pragma weak I2C2_ER_IRQHandler = Default_Handler
+#pragma weak SPI1_IRQHandler = Default_Handler
+#pragma weak SPI2_IRQHandler = Default_Handler
+#pragma weak USART1_IRQHandler = Default_Handler
+#pragma weak USART2_IRQHandler = Default_Handler
+#pragma weak USART3_IRQHandler = Default_Handler
+#pragma weak EXTI15_10_IRQHandler = Default_Handler
+#pragma weak RTCAlarm_IRQHandler = Default_Handler
+#pragma weak USBWakeUp_IRQHandler = Default_Handler
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.cpp b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..ab57d617943639d5731c0384377c1b9d1915c497
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.cpp
@@ -0,0 +1,306 @@
+/***************************************************************************
+ *   Copyright (C) 2017 by Terraneo Federico                               *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   As a special exception, if other files instantiate templates or use   *
+ *   macros or inline functions from this file, or you compile this file   *
+ *   and link it with other works to produce a work based on this file,    *
+ *   this file does not by itself cause the resulting work to be covered   *
+ *   by the GNU General Public License. However the source code for this   *
+ *   file must still be made available in accordance with the GNU General  *
+ *   Public License. This exception does not invalidate any other reasons  *
+ *   why a work based on this file might be covered by the GNU General     *
+ *   Public License.                                                       *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/
+
+#include "rtc.h"
+#include <miosix.h>
+#include <sys/ioctl.h>
+#include <kernel/scheduler/scheduler.h>
+
+using namespace miosix;
+
+namespace {
+
+//
+// class ScopedCnf, RAII to allow writing to the RTC alarm and prescaler.
+// NOTE: datasheet says that after CNF bit has been cleared, no write is allowed
+// to *any* of the RTC registers, not just PRL,CNT,ALR until RTOFF goes to 1.
+// We do not wait until RTOFF is 1 in the destructor for performance reasons,
+// so the rest of the code must be careful.
+//
+class ScopedCnf
+{
+public:
+    ScopedCnf()
+    {
+        while((RTC->CRL & RTC_CRL_RTOFF)==0) ;
+        RTC->CRL=0b11111;
+    }
+    
+    ~ScopedCnf()
+    {
+        RTC->CRL=0b01111;
+    }
+};
+
+long long swTime=0;      //64bit software extension of current time in ticks
+long long irqTime=0;     //64bit software extension of scheduled irq time in ticks
+Thread *waiting=nullptr; //waiting thread
+
+/**
+ * \return the hardware counter
+ */
+inline unsigned int IRQgetHwTick()
+{
+    unsigned int h1=RTC->CNTH;
+    unsigned int l1=RTC->CNTL;
+    unsigned int h2=RTC->CNTH;
+    if(h1==h2) return (h1<<16) | l1;
+    return (h2<<16) | RTC->CNTL;
+}
+
+/**
+ * \return the time in ticks (hardware part + software extension to 64bits)
+ */
+long long IRQgetTick()
+{
+    //Pending bit trick
+    unsigned int hwTime=IRQgetHwTick();
+    if((RTC->CRL & RTC_CRL_OWF) && IRQgetHwTick()>=hwTime)
+        return (swTime + static_cast<long long>(hwTime)) + (1LL<<32);
+    return swTime + static_cast<long long>(hwTime);
+}
+
+/**
+ * Sleep the current thread till the specified time
+ * \param tick absolute time in ticks
+ * \param dLock used to reenable interrupts while sleeping
+ * \return true if the wait time was in the past
+ */
+bool IRQabsoluteWaitTick(long long tick, FastInterruptDisableLock& dLock)
+{
+    irqTime=tick;
+    unsigned int hwAlarm=(tick & 0xffffffffULL) - (swTime & 0xffffffffULL);
+    {
+        ScopedCnf cnf;
+        RTC->ALRL=hwAlarm;
+        RTC->ALRH=hwAlarm>>16;
+    }
+    //NOTE: We do not wait for the alarm register to be written back to the low
+    //frequency domain for performance reasons. The datasheet says it takes
+    //at least 3 cycles of the 32KHz clock, but experiments show that it takes
+    //from 2 to 3, so perhaps they meant "at most 3". Because of this we
+    //consider the time in the past if we are more than 2 ticks of the 16KHz
+    //clock (4 ticks of the 32KHz one) in advance. Sleeps less than 122us are
+    //thus not supported.
+    if(IRQgetTick()>=tick-2) return true;
+    waiting=Thread::IRQgetCurrentThread();
+    do {
+        Thread::IRQwait();
+        {
+            FastInterruptEnableLock eLock(dLock);
+            Thread::yield();
+        }
+    } while(waiting);
+    return false;
+}
+
+} //anon namespace
+
+/**
+ * RTC interrupt
+ */
+void __attribute__((naked)) RTC_IRQHandler()
+{
+    saveContext();
+    asm volatile("bl _Z10RTCIrqImplv");
+    restoreContext();
+}
+
+/**
+ * RTC interrupt actual implementation
+ */
+void __attribute__((used)) RTCIrqImpl()
+{
+    unsigned int crl=RTC->CRL;
+    if(crl & RTC_CRL_OWF)
+    {
+        RTC->CRL=(RTC->CRL | 0xf) & ~RTC_CRL_OWF;
+        swTime+=1LL<<32;
+    } else if(crl & RTC_CRL_ALRF) {
+        RTC->CRL=(RTC->CRL | 0xf) & ~RTC_CRL_ALRF;
+        if(waiting && IRQgetTick()>=irqTime)
+        {
+            waiting->IRQwakeup();
+            if(waiting->IRQgetPriority()>
+                Thread::IRQgetCurrentThread()->IRQgetPriority())
+                    Scheduler::IRQfindNextThread();
+            waiting=nullptr;
+        }
+    }
+}
+
+namespace miosix {
+
+void absoluteDeepSleep(long long int value)
+{
+    const long long wakeupAdvance=3; //waking up takes time
+    
+    Rtc& rtc=Rtc::instance();
+    ioctl(STDOUT_FILENO,IOCTL_SYNC,0);
+
+    FastInterruptDisableLock dLock;
+    
+    //Set alarm and enable EXTI
+    long long tick=rtc.tc.ns2tick(value)-wakeupAdvance;
+    unsigned int hwAlarm=(tick & 0xffffffffULL) - (swTime & 0xffffffffULL);
+    {
+        ScopedCnf cnf;
+        RTC->ALRL=hwAlarm;
+        RTC->ALRH=hwAlarm>>16;
+    }
+    while((RTC->CRL & RTC_CRL_RTOFF)==0) ;
+    
+    
+    EXTI->RTSR |= EXTI_RTSR_TR17;
+    EXTI->EMR  |= EXTI_EMR_MR17; //enable event for wakeup
+    
+    while(IRQgetTick()<tick)
+    {
+        PWR->CR |= PWR_CR_LPDS;
+        SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+        // Using WFE instead of WFI because if while we are with interrupts
+        // disabled an interrupt (such as the tick interrupt) occurs, it
+        // remains pending and the WFI becomes a nop, and the device never goes
+        // in sleep mode. WFE events are latched in a separate pending register
+        // so interrupts do not interfere with them       
+        __WFE();
+        SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk;
+        PWR->CR &= ~PWR_CR_LPDS;
+        
+        #ifndef SYSCLK_FREQ_24MHz
+        #error TODO: support more PLL frequencies
+        #endif
+        //STOP mode resets the clock to the HSI 8MHz, so restore the 24MHz clock
+        #ifndef RUN_WITH_HSI
+        RCC->CR |= RCC_CR_HSEON;
+        while((RCC->CR & RCC_CR_HSERDY)==0) ;
+        //PLL = (HSE / 2) * 6 = 24 MHz
+        RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL);
+        RCC->CFGR |=   RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL6;
+        #else //RUN_WITH_HSI
+        //PLL = (HSI / 2) * 6 = 24 MHz
+        RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL);
+        RCC->CFGR |=                     RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL6;
+        #endif //RUN_WITH_HSI        
+        RCC->CR |= RCC_CR_PLLON;
+        while((RCC->CR & RCC_CR_PLLRDY)==0) ;
+        RCC->CFGR &= ~RCC_CFGR_SW;
+        RCC->CFGR |= RCC_CFGR_SW_PLL;    
+        while((RCC->CFGR & RCC_CFGR_SWS)!=0x08) ;
+        
+        //Wait RSF
+        RTC->CRL=(RTC->CRL | 0xf) & ~RTC_CRL_RSF;
+        while((RTC->CRL & RTC_CRL_RSF)==0) ;
+        
+        //Clear IRQ
+        unsigned int crl=RTC->CRL;
+        if(crl & RTC_CRL_OWF)
+        {
+            //TODO: check that an overflow does cause a wakeup just like alarm
+            RTC->CRL=(RTC->CRL | 0xf) & ~RTC_CRL_OWF;
+            swTime+=1LL<<32;
+        } else if(crl & RTC_CRL_ALRF) {
+            RTC->CRL=(RTC->CRL | 0xf) & ~RTC_CRL_ALRF;
+        }
+    }
+    
+    EXTI->EMR &=~ EXTI_EMR_MR17; //disable event for wakeup
+    
+    tick+=wakeupAdvance;
+    while(IRQgetTick()<tick) ;
+}
+
+//
+// class Rtc
+//
+
+Rtc& Rtc::instance()
+{
+    static Rtc singleton;
+    return singleton;
+}
+
+long long Rtc::getValue() const
+{
+    //Function takes ~170 clock cycles ~60 cycles IRQgetTick, ~96 cycles tick2ns
+    long long tick;
+    {
+        FastInterruptDisableLock dLock;
+        tick=IRQgetTick();
+    }
+    //tick2ns is reentrant, so can be called with interrupt enabled
+    return tc.tick2ns(tick);
+}
+
+long long Rtc::IRQgetValue() const
+{
+    return tc.tick2ns(IRQgetTick());
+}
+
+void Rtc::setValue(long long value)
+{
+    FastInterruptDisableLock dLock;
+    swTime=tc.ns2tick(value)-IRQgetHwTick();
+}
+
+void Rtc::wait(long long value)
+{
+    FastInterruptDisableLock dLock;
+    IRQabsoluteWaitTick(IRQgetTick()+tc.ns2tick(value),dLock);
+}
+
+bool Rtc::absoluteWait(long long value)
+{
+    FastInterruptDisableLock dLock;
+    return IRQabsoluteWaitTick(tc.ns2tick(value),dLock);
+}
+
+Rtc::Rtc() : tc(getTickFrequency())
+{
+    {
+        FastInterruptDisableLock dLock;
+        RCC->APB1ENR |= RCC_APB1ENR_PWREN | RCC_APB1ENR_BKPEN;
+        PWR->CR |= PWR_CR_DBP;
+        RCC->BDCR=RCC_BDCR_RTCEN       //RTC enabled
+                | RCC_BDCR_LSEON       //External 32KHz oscillator enabled
+                | RCC_BDCR_RTCSEL_0;   //Select LSE as clock source for RTC
+        RCC_SYNC();
+        BKP->RTCCR=BKP_RTCCR_CCO;      //Output RTC clock/64 on pin
+    }
+    while((RCC->BDCR & RCC_BDCR_LSERDY)==0) ; //Wait for LSE to start
+    
+    RTC->CRH=RTC_CRH_OWIE | RTC_CRH_ALRIE;
+    {
+        ScopedCnf cnf;
+        RTC->PRLH=0;
+        RTC->PRLL=1;
+    }
+    NVIC_SetPriority(RTC_IRQn,5);
+    NVIC_EnableIRQ(RTC_IRQn);
+}
+
+} //namespace miosix
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.h b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.h
new file mode 100644
index 0000000000000000000000000000000000000000..c41944217c42c7a6193dec80f7e4069f210b629b
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/drivers/rtc.h
@@ -0,0 +1,109 @@
+/***************************************************************************
+ *   Copyright (C) 2017 by Terraneo Federico                               *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   As a special exception, if other files instantiate templates or use   *
+ *   macros or inline functions from this file, or you compile this file   *
+ *   and link it with other works to produce a work based on this file,    *
+ *   this file does not by itself cause the resulting work to be covered   *
+ *   by the GNU General Public License. However the source code for this   *
+ *   file must still be made available in accordance with the GNU General  *
+ *   Public License. This exception does not invalidate any other reasons  *
+ *   why a work based on this file might be covered by the GNU General     *
+ *   Public License.                                                       *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/
+
+#ifndef RTC_H
+#define RTC_H
+
+#include <kernel/timeconversion.h>
+
+namespace miosix {
+
+/**
+ * Puts the MCU in deep sleep until the specified absolute time.
+ * \param value absolute wait time in nanoseconds
+ * If value of absolute time is in the past no waiting will be set
+ * and function return immediately.
+ */
+void absoluteDeepSleep(long long value);
+
+/**
+ * Driver for the stm32 RTC.
+ * All the wait and deepSleep functions cannot be called concurrently by
+ * multiple threads.
+ */
+class Rtc
+{
+public:
+    /**
+     * \return an instance of this class
+     */
+    static Rtc& instance();
+
+    /**
+     * \return the timer counter value in nanoseconds
+     */
+    long long getValue() const;
+
+    /**
+     * \return the timer counter value in nanoseconds
+     * 
+     * Can be called with interrupt disabled, or inside an interrupt
+     */
+    long long IRQgetValue() const;
+
+    /**
+     * Set the timer counter value
+     * \param value new timer value in nanoseconds
+     * 
+     * NOTE: if alarm is set wakeup time is not updated
+     */
+    void setValue(long long value);
+    
+    /**
+     * Put thread in wait for the specified relative time.
+     * This function wait for a relative time passed as parameter.
+     * \param value relative time to wait, expressed in nanoseconds
+     */
+    void wait(long long value);
+    
+    /**
+     * Puts the thread in wait until the specified absolute time.
+     * \param value absolute wait time in nanoseconds
+     * If value of absolute time is in the past no waiting will be set
+     * and function return immediately.
+     * \return true if the wait time was in the past
+     */
+    bool absoluteWait(long long value);
+
+    /**
+     * \return the timer frequency in Hz
+     */
+    unsigned int getTickFrequency() const { return 16384; }
+
+private:
+    Rtc();
+    Rtc(const Rtc&)=delete;
+    Rtc& operator= (const Rtc&)=delete;
+    
+    TimeConversion tc;
+    
+    friend void absoluteDeepSleep(long long value);
+};
+
+} //namespace miosix
+
+#endif //RTC_H
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp.cpp b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0c92ed31746328dea927df612445548ed11ea9dc
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp.cpp
@@ -0,0 +1,88 @@
+/***************************************************************************
+ *   Copyright (C) 2015, 2016, 2017, 2018 by Terraneo Federico             *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   As a special exception, if other files instantiate templates or use   *
+ *   macros or inline functions from this file, or you compile this file   *
+ *   and link it with other works to produce a work based on this file,    *
+ *   this file does not by itself cause the resulting work to be covered   *
+ *   by the GNU General Public License. However the source code for this   *
+ *   file must still be made available in accordance with the GNU General  *
+ *   Public License. This exception does not invalidate any other reasons  *
+ *   why a work based on this file might be covered by the GNU General     *
+ *   Public License.                                                       *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/ 
+
+/***********************************************************************
+ * bsp.cpp Part of the Miosix Embedded OS.
+ * Board support package, this file initializes hardware.
+ ************************************************************************/
+
+#include <utility>
+#include <sys/ioctl.h>
+#include "interfaces/bsp.h"
+#include "interfaces/delays.h"
+#include "interfaces/arch_registers.h"
+#include "config/miosix_settings.h"
+#include "filesystem/file_access.h"
+#include "filesystem/console/console_device.h"
+#include "drivers/serial.h"
+#include "board_settings.h"
+
+using namespace std;
+
+namespace miosix {
+
+//
+// Initialization
+//
+
+void IRQbspInit()
+{
+    //Enable all gpios, as well as AFIO, SPI1, TIM3
+    RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
+                    RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN |
+                    RCC_APB2ENR_AFIOEN | RCC_APB2ENR_SPI1EN;
+    RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+    RCC_SYNC();
+
+    DefaultConsole::instance().IRQset(intrusive_ref_ptr<Device>(
+        new STM32Serial(defaultSerial,defaultSerialSpeed,
+        defaultSerialFlowctrl ? STM32Serial::RTSCTS : STM32Serial::NOFLOWCTRL)));
+}
+
+void bspInit2()
+{
+    
+}
+
+//
+// Shutdown and reboot
+//
+
+void shutdown()
+{
+    reboot(); //This board has no shutdown support, so we reboot on shutdown
+}
+
+void reboot()
+{
+    ioctl(STDOUT_FILENO,IOCTL_SYNC,0);
+
+    disableInterrupts();
+    miosix_private::IRQsystemReboot();
+}
+
+} //namespace miosix
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp_impl.h b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp_impl.h
new file mode 100644
index 0000000000000000000000000000000000000000..04c8f7e5ad95f3ecc1a8fc15921a065e1b55cbd4
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/interfaces-impl/bsp_impl.h
@@ -0,0 +1,61 @@
+/***************************************************************************
+ *   Copyright (C) 2018 by Terraneo Federico                               *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   As a special exception, if other files instantiate templates or use   *
+ *   macros or inline functions from this file, or you compile this file   *
+ *   and link it with other works to produce a work based on this file,    *
+ *   this file does not by itself cause the resulting work to be covered   *
+ *   by the GNU General Public License. However the suorce code for this   *
+ *   file must still be made available in accordance with the GNU General  *
+ *   Public License. This exception does not invalidate any other reasons  *
+ *   why a work based on this file might be covered by the GNU General     *
+ *   Public License.                                                       *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/ 
+
+/***********************************************************************
+* bsp_impl.h Part of the Miosix Embedded OS.
+* Board support package, this file initializes hardware.
+************************************************************************/
+
+#ifndef BSP_IMPL_H
+#define BSP_IMPL_H
+
+namespace miosix {
+
+/**
+\addtogroup Hardware
+\{
+*/
+
+inline void ledOn() {}
+inline void ledOff() {}
+
+/**
+ * Polls the SD card sense GPIO
+ * \return true if there is an uSD card in the socket.
+ */
+inline bool sdCardSense()
+{
+    return true;
+}
+
+/**
+\}
+*/
+
+} //namespace miosix
+
+#endif //BSP_IMPL_H
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_128k+20k_rom.ld b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_128k+20k_rom.ld
new file mode 100644
index 0000000000000000000000000000000000000000..871ca1220e854880e6782a20a84f04ca36a28986
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_128k+20k_rom.ld
@@ -0,0 +1,171 @@
+/*
+ * C++ enabled linker script for stm32 (128K FLASH, 20K RAM)
+ * Last 1K of FLASH is reserved as non-volatile storage by the BSP
+ * Developed by TFT: Terraneo Federico Technologies
+ * Optimized for use with the Miosix kernel
+ */
+
+/*
+ * This linker script puts:
+ * - read only data and code (.text, .rodata, .eh_*) in flash
+ * - stacks, heap and sections .data and .bss in the internal ram
+ * - the external ram (if available) is not used.
+ */
+
+/*
+ * The main stack is used for interrupt handling by the kernel.
+ *
+ * *** Readme ***
+ * This linker script places the main stack (used by the kernel for interrupts)
+ * at the bottom of the ram, instead of the top. This is done for two reasons:
+ *
+ * - as an optimization for microcontrollers with little ram memory. In fact
+ *   the implementation of malloc from newlib requests memory to the OS in 4KB
+ *   block (except the first block that can be smaller). This is probably done
+ *   for compatibility with OSes with an MMU and paged memory. To see why this
+ *   is bad, consider a microcontroller with 8KB of ram: when malloc finishes
+ *   up the first 4KB it will call _sbrk_r asking for a 4KB block, but this will
+ *   fail because the top part of the ram is used by the main stack. As a
+ *   result, the top part of the memory will not be used by malloc, even if
+ *   available (and it is nearly *half* the ram on an 8KB mcu). By placing the
+ *   main stack at the bottom of the ram, the upper 4KB block will be entirely
+ *   free and available as heap space.
+ *
+ * - In case of main stack overflow the cpu will fault because access to memory
+ *   before the beginning of the ram faults. Instead with the default stack
+ *   placement the main stack will silently collide with the heap.
+ * Note: if increasing the main stack size also increase the ORIGIN value in
+ * the MEMORY definitions below accordingly.
+ */
+_main_stack_size = 0x00000200;                     /* main stack = 512Bytes */
+_main_stack_top  = 0x20000000 + _main_stack_size;
+ASSERT(_main_stack_size   % 8 == 0, "MAIN stack size error");
+
+/* end of the heap on 20KB microcontrollers */
+_heap_end = 0x20005000;                            /* end of available ram  */
+
+/* identify the Entry Point  */
+ENTRY(_Z13Reset_Handlerv)
+
+/* specify the memory areas  */
+MEMORY
+{
+    flash(rx)   : ORIGIN = 0x08000000, LENGTH = 128K
+
+    /*
+     * Note, the ram starts at 0x20000000 but it is necessary to add the size
+     * of the main stack, so it is 0x20000200.
+     */
+    ram(wx)     : ORIGIN = 0x20000200, LENGTH =  20K-0x200
+}
+
+/* now define the output sections  */
+SECTIONS
+{
+    . = 0;
+    
+    /* .text section: code goes to flash */
+    .text :
+    {
+        /* Startup code must go at address 0 */
+        KEEP(*(.isr_vector))
+        
+        *(.text)
+        *(.text.*)
+        *(.gnu.linkonce.t.*)
+        /* these sections for thumb interwork? */
+        *(.glue_7)
+        *(.glue_7t)
+        /* these sections for C++? */
+        *(.gcc_except_table)
+        *(.gcc_except_table.*)
+        *(.ARM.extab*)
+        *(.gnu.linkonce.armextab.*)
+
+        . = ALIGN(4);
+        /* .rodata: constant data */
+        *(.rodata)
+        *(.rodata.*)
+        *(.gnu.linkonce.r.*)
+
+        /* C++ Static constructors/destructors (eabi) */
+        . = ALIGN(4);
+        KEEP(*(.init))
+        
+        . = ALIGN(4);
+        __miosix_init_array_start = .;
+        KEEP (*(SORT(.miosix_init_array.*)))
+        KEEP (*(.miosix_init_array))
+        __miosix_init_array_end = .;
+
+        . = ALIGN(4);
+        __preinit_array_start = .;
+        KEEP (*(.preinit_array))
+        __preinit_array_end = .;
+
+        . = ALIGN(4);
+        __init_array_start = .;
+        KEEP (*(SORT(.init_array.*)))
+        KEEP (*(.init_array))
+        __init_array_end = .;
+
+        . = ALIGN(4);
+        KEEP(*(.fini))
+
+        . = ALIGN(4);
+        __fini_array_start = .;
+        KEEP (*(.fini_array))
+        KEEP (*(SORT(.fini_array.*)))
+        __fini_array_end = .;
+
+        /* C++ Static constructors/destructors (elf)  */
+        . = ALIGN(4);
+        _ctor_start = .;
+        KEEP (*crtbegin.o(.ctors))
+        KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+        KEEP (*(SORT(.ctors.*)))
+        KEEP (*crtend.o(.ctors))
+       _ctor_end = .;
+
+        . = ALIGN(4);
+        KEEP (*crtbegin.o(.dtors))
+        KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+        KEEP (*(SORT(.dtors.*)))
+        KEEP (*crtend.o(.dtors))
+    } > flash
+
+    /* .ARM.exidx is sorted, so has to go in its own output section.  */
+    __exidx_start = .;
+    .ARM.exidx :
+    {
+        *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+    } > flash
+    __exidx_end = .;
+
+	/* .data section: global variables go to ram, but also store a copy to
+       flash to initialize them */
+    .data : ALIGN(8)
+    {
+        _data = .;
+        *(.data)
+        *(.data.*)
+        *(.gnu.linkonce.d.*)
+        . = ALIGN(8);
+        _edata = .;
+    } > ram AT > flash
+    _etext = LOADADDR(.data);
+
+    /* .bss section: uninitialized global variables go to ram */
+    _bss_start = .;
+    .bss :
+    {
+        *(.bss)
+        *(.bss.*)
+        *(.gnu.linkonce.b.*)
+        . = ALIGN(8);
+    } > ram
+    _bss_end = .;
+
+    _end = .;
+    PROVIDE(end = .);
+}
diff --git a/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_64k+20k_rom.ld b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_64k+20k_rom.ld
new file mode 100644
index 0000000000000000000000000000000000000000..106a1f3c6316d8d44e6227f34f44dfa144737d0b
--- /dev/null
+++ b/miosix/arch/cortexM3_stm32/stm32f103cx_generic/stm32_64k+20k_rom.ld
@@ -0,0 +1,171 @@
+/*
+ * C++ enabled linker script for stm32 (64K FLASH, 20K RAM)
+ * Last 1K of FLASH is reserved as non-volatile storage by the BSP
+ * Developed by TFT: Terraneo Federico Technologies
+ * Optimized for use with the Miosix kernel
+ */
+
+/*
+ * This linker script puts:
+ * - read only data and code (.text, .rodata, .eh_*) in flash
+ * - stacks, heap and sections .data and .bss in the internal ram
+ * - the external ram (if available) is not used.
+ */
+
+/*
+ * The main stack is used for interrupt handling by the kernel.
+ *
+ * *** Readme ***
+ * This linker script places the main stack (used by the kernel for interrupts)
+ * at the bottom of the ram, instead of the top. This is done for two reasons:
+ *
+ * - as an optimization for microcontrollers with little ram memory. In fact
+ *   the implementation of malloc from newlib requests memory to the OS in 4KB
+ *   block (except the first block that can be smaller). This is probably done
+ *   for compatibility with OSes with an MMU and paged memory. To see why this
+ *   is bad, consider a microcontroller with 8KB of ram: when malloc finishes
+ *   up the first 4KB it will call _sbrk_r asking for a 4KB block, but this will
+ *   fail because the top part of the ram is used by the main stack. As a
+ *   result, the top part of the memory will not be used by malloc, even if
+ *   available (and it is nearly *half* the ram on an 8KB mcu). By placing the
+ *   main stack at the bottom of the ram, the upper 4KB block will be entirely
+ *   free and available as heap space.
+ *
+ * - In case of main stack overflow the cpu will fault because access to memory
+ *   before the beginning of the ram faults. Instead with the default stack
+ *   placement the main stack will silently collide with the heap.
+ * Note: if increasing the main stack size also increase the ORIGIN value in
+ * the MEMORY definitions below accordingly.
+ */
+_main_stack_size = 0x00000200;                     /* main stack = 512Bytes */
+_main_stack_top  = 0x20000000 + _main_stack_size;
+ASSERT(_main_stack_size   % 8 == 0, "MAIN stack size error");
+
+/* end of the heap on 20KB microcontrollers */
+_heap_end = 0x20005000;                            /* end of available ram  */
+
+/* identify the Entry Point  */
+ENTRY(_Z13Reset_Handlerv)
+
+/* specify the memory areas  */
+MEMORY
+{
+    flash(rx)   : ORIGIN = 0x08000000, LENGTH = 64K
+
+    /*
+     * Note, the ram starts at 0x20000000 but it is necessary to add the size
+     * of the main stack, so it is 0x20000200.
+     */
+    ram(wx)     : ORIGIN = 0x20000200, LENGTH =  20K-0x200
+}
+
+/* now define the output sections  */
+SECTIONS
+{
+    . = 0;
+    
+    /* .text section: code goes to flash */
+    .text :
+    {
+        /* Startup code must go at address 0 */
+        KEEP(*(.isr_vector))
+        
+        *(.text)
+        *(.text.*)
+        *(.gnu.linkonce.t.*)
+        /* these sections for thumb interwork? */
+        *(.glue_7)
+        *(.glue_7t)
+        /* these sections for C++? */
+        *(.gcc_except_table)
+        *(.gcc_except_table.*)
+        *(.ARM.extab*)
+        *(.gnu.linkonce.armextab.*)
+
+        . = ALIGN(4);
+        /* .rodata: constant data */
+        *(.rodata)
+        *(.rodata.*)
+        *(.gnu.linkonce.r.*)
+
+        /* C++ Static constructors/destructors (eabi) */
+        . = ALIGN(4);
+        KEEP(*(.init))
+        
+        . = ALIGN(4);
+        __miosix_init_array_start = .;
+        KEEP (*(SORT(.miosix_init_array.*)))
+        KEEP (*(.miosix_init_array))
+        __miosix_init_array_end = .;
+
+        . = ALIGN(4);
+        __preinit_array_start = .;
+        KEEP (*(.preinit_array))
+        __preinit_array_end = .;
+
+        . = ALIGN(4);
+        __init_array_start = .;
+        KEEP (*(SORT(.init_array.*)))
+        KEEP (*(.init_array))
+        __init_array_end = .;
+
+        . = ALIGN(4);
+        KEEP(*(.fini))
+
+        . = ALIGN(4);
+        __fini_array_start = .;
+        KEEP (*(.fini_array))
+        KEEP (*(SORT(.fini_array.*)))
+        __fini_array_end = .;
+
+        /* C++ Static constructors/destructors (elf)  */
+        . = ALIGN(4);
+        _ctor_start = .;
+        KEEP (*crtbegin.o(.ctors))
+        KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+        KEEP (*(SORT(.ctors.*)))
+        KEEP (*crtend.o(.ctors))
+       _ctor_end = .;
+
+        . = ALIGN(4);
+        KEEP (*crtbegin.o(.dtors))
+        KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+        KEEP (*(SORT(.dtors.*)))
+        KEEP (*crtend.o(.dtors))
+    } > flash
+
+    /* .ARM.exidx is sorted, so has to go in its own output section.  */
+    __exidx_start = .;
+    .ARM.exidx :
+    {
+        *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+    } > flash
+    __exidx_end = .;
+
+	/* .data section: global variables go to ram, but also store a copy to
+       flash to initialize them */
+    .data : ALIGN(8)
+    {
+        _data = .;
+        *(.data)
+        *(.data.*)
+        *(.gnu.linkonce.d.*)
+        . = ALIGN(8);
+        _edata = .;
+    } > ram AT > flash
+    _etext = LOADADDR(.data);
+
+    /* .bss section: uninitialized global variables go to ram */
+    _bss_start = .;
+    .bss :
+    {
+        *(.bss)
+        *(.bss.*)
+        *(.gnu.linkonce.b.*)
+        . = ALIGN(8);
+    } > ram
+    _bss_end = .;
+
+    _end = .;
+    PROVIDE(end = .);
+}
diff --git a/miosix/config/Makefile.inc b/miosix/config/Makefile.inc
index c56dc78ff49b9a9bfb5a7e649a9e6e6e666458b9..5ec71afbc91cc49a6c4e04cbf9a18beef858cf4d 100644
--- a/miosix/config/Makefile.inc
+++ b/miosix/config/Makefile.inc
@@ -43,6 +43,7 @@
 #OPT_BOARD := stm32h753xi_eval
 #OPT_BOARD := stm32f407vg_thermal_test_chip
 #OPT_BOARD := stm32f205_generic
+#OPT_BOARD := stm32f103cx_generic
 
 ##
 ## Optimization flags, choose one.
@@ -504,6 +505,27 @@ endif
 
 # No options
 
+##---------------------------------------------------------------------------
+## stm32f103cx_generic
+##
+
+ifeq ($(OPT_BOARD),stm32f103cx_generic)
+    
+    # stm32f103c8 has 64K, stm32f103cb has 128K
+    LINKER_SCRIPT_PATH := arch/cortexM3_stm32/stm32f103cx_generic/
+    #LINKER_SCRIPT := $(LINKER_SCRIPT_PATH)stm32_64k+20k_rom.ld
+    LINKER_SCRIPT := $(LINKER_SCRIPT_PATH)stm32_128k+20k_rom.ld
+    
+    ## Select clock frequency
+    CLOCK_FREQ := -DSYSCLK_FREQ_24MHz=24000000 -DRUN_WITH_HSI
+    #CLOCK_FREQ := -DSYSCLK_FREQ_24MHz=24000000
+    #CLOCK_FREQ := -DSYSCLK_FREQ_36MHz=36000000
+    #CLOCK_FREQ := -DSYSCLK_FREQ_48MHz=48000000
+    #CLOCK_FREQ := -DSYSCLK_FREQ_56MHz=56000000
+    #CLOCK_FREQ := -DSYSCLK_FREQ_72MHz=72000000
+
+endif
+
 ############################################################################
 ## From the options selected above, now fill all the variables needed to  ##
 ## build Miosix. You should modify something here only if you are adding  ##
@@ -583,6 +605,8 @@ else ifeq ($(OPT_BOARD),stm32f407vg_thermal_test_chip)
     ARCH := cortexM4_stm32f4
 else ifeq ($(OPT_BOARD),stm32f205_generic)
     ARCH := cortexM3_stm32f2
+else ifeq ($(OPT_BOARD),stm32f103cx_generic)
+    ARCH := cortexM3_stm32
 else
     $(info Error: no board specified in miosix/config/Makefile.inc)
     $(error Error)
@@ -1031,6 +1055,37 @@ else ifeq ($(ARCH),cortexM3_stm32)
         ## error message saying that 'make program' is not supported for that
         ## board.
         PROGRAM_CMDLINE := stm32flash -w main.hex -v /dev/ttyUSB0
+        
+    ##-------------------------------------------------------------------------
+    ## BOARD: stm32f103cx_generic
+    ##
+    else ifeq ($(OPT_BOARD),stm32f103cx_generic)
+
+        ## Base directory with header files for this board
+        BOARD_INC := arch/cortexM3_stm32/stm32f103cx_generic
+
+        ## Select linker script and boot file
+        ## Their path must be relative to the miosix directory.
+        BOOT_FILE := $(BOARD_INC)/core/stage_1_boot.o
+        #LINKER_SCRIPT := already selected in board options
+
+        ## Select architecture specific files
+        ## These are the files in arch/<arch name>/<board name>
+        ARCH_SRC :=                                  \
+        $(BOARD_INC)/interfaces-impl/bsp.cpp         \
+        $(BOARD_INC)/drivers/rtc.cpp
+
+        ## Add a #define to allow querying board name
+        CFLAGS_BASE   += -D_BOARD_STM32F103CX_GENERIC -DSTM32F10X_MD_VL 
+        CXXFLAGS_BASE += -D_BOARD_STM32F103CX_GENERIC -DSTM32F10X_MD_VL
+
+        ## Select programmer command line
+        ## This is the program that is invoked when the user types
+        ## 'make program'
+        ## The command must provide a way to program the board, or print an
+        ## error message saying that 'make program' is not supported for that
+        ## board.
+        PROGRAM_CMDLINE := stm32flash -w main.hex -v /dev/ttyUSB0
     
     ##-------------------------------------------------------------------------
     ## End of board list
diff --git a/miosix/config/arch/cortexM3_stm32/stm32f103cx_generic/board_settings.h b/miosix/config/arch/cortexM3_stm32/stm32f103cx_generic/board_settings.h
new file mode 100644
index 0000000000000000000000000000000000000000..9b01851771898efc5b0b429d935ca5d7612c81bd
--- /dev/null
+++ b/miosix/config/arch/cortexM3_stm32/stm32f103cx_generic/board_settings.h
@@ -0,0 +1,76 @@
+/***************************************************************************
+ *   Copyright (C) 2018 by Terraneo Federico                               *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   As a special exception, if other files instantiate templates or use   *
+ *   macros or inline functions from this file, or you compile this file   *
+ *   and link it with other works to produce a work based on this file,    *
+ *   this file does not by itself cause the resulting work to be covered   *
+ *   by the GNU General Public License. However the source code for this   *
+ *   file must still be made available in accordance with the GNU General  *
+ *   Public License. This exception does not invalidate any other reasons  *
+ *   why a work based on this file might be covered by the GNU General     *
+ *   Public License.                                                       *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/
+
+#ifndef BOARD_SETTINGS_H
+#define	BOARD_SETTINGS_H
+
+#include "util/version.h"
+
+/**
+ * \internal
+ * Versioning for board_settings.h for out of git tree projects
+ */
+#define BOARD_SETTINGS_VERSION 100
+
+namespace miosix {
+
+/**
+ * \addtogroup Settings
+ * \{
+ */
+
+/// Size of stack for main().
+/// The C standard library is stack-heavy (iprintf requires 1KB)
+const unsigned int MAIN_STACK_SIZE=2048;
+
+/// Frequency of tick (in Hz)
+/// For the priority scheduler this is also the context switch frequency
+const unsigned int TICK_FREQ=1000;
+
+///\internal Aux timer run @ 100KHz
+///Note that since the timer is only 16 bits this imposes a limit on the
+///burst measurement of 655ms. If due to a pause_kernel() or
+///disable_interrupts() section a thread runs for more than that time, a wrong
+///burst value will be measured
+const unsigned int AUX_TIMER_CLOCK=100000;
+const unsigned int AUX_TIMER_MAX=0xffff; ///<\internal Aux timer is 16 bits
+
+/// Serial port
+const unsigned int defaultSerial=1;
+const unsigned int defaultSerialSpeed=19200;
+const bool defaultSerialFlowctrl=false;
+#define SERIAL_1_DMA
+//#define SERIAL_2_DMA //Serial 1 is not used, so not enabling DMA
+//#define SERIAL_3_DMA //Serial 1 is not used, so not enabling DMA
+
+/**
+ * \}
+ */
+
+} //namespace miosix
+
+#endif	/* BOARD_SETTINGS_H */