Przeglądaj źródła

Initial commit.

Konstantin Oblaukhov 14 lat temu
commit
4e7a1e4218

+ 39 - 0
README

@@ -0,0 +1,39 @@
+== About ==
+This project is used to develop applications for stm32 - ST's ARM Cortex-M3 MCUs, using cmake, GCC, newlib (libc) and STM32F10x Standard Peripherals Library.
+Requirements:
+* cmake >= 2.6
+* GCC toolchain with newlib.
+* STM32F10x Standard Peripherals Library
+Project contains:
+* CMake toolchain file, that configures cmake to use arm toolchain, and sets some variables for STM32F10x Standard Peripherals Library.
+* CMake project template.
+* Example projects
+** blinky - blink LED using timers and PWM.
+** newlib - show date from RTC using uart and libc functions from newlib
+== Usage ==
+=== Configure ===
+First of all you need to configure toolchain, you can do this by editing values in stm32.cmake or pass it throught command line.
+Variables for toolchain:
+* TOOLCHAIN_PREFIX - where toolchain is located, '''default''': /usr
+* STM32_StdPeriphLib_DIR - path to STM32F10x Standard Peripherals Library '''default''': /opt/STM32F10x_StdPeriph_Lib_V3.5.0
+* TARGET_TRIPLET - toolchain target triplet, '''default''': arm-none-eabi
+Than you need to adjust some variables in CMakeLists.txt (example for stm32f103ve):
+* PROJECT(stm32-blinky) - Set the project name.
+* SET(STM32_FLASH_SIZE "512K") - Select chip's flash size.
+* SET(STM32_RAM_SIZE "64K") - Select chip's RAM size.
+* SET(STM32_STACK_ADDRESS "0x20010000") - Select stack address = ram origin + ram size
+* SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DSTM32F10X_HD") - Select your device type in defines (CL, HD, HD_VL, LD, LD_VL, MD, MD_VL, XL, more information in StdPeriphLib)
+* SET(STARTUP_SOURCE ${STM32_STARTUP_HD}) - Select your device type for startup files (CL, HD, HD_VL, LD, LD_VL, MD, MD_VL, XL, more information in StdPeriphLib)
+* MOD_SOURCES contains list of StdPeriphLib's modules needed for project.
+* All projects sources should be listed in PROJECT_SOURCES variable.
+Also, you need to adjust StdPeriphLib modules in stm32f10x_conf.h.
+=== Building ===
+Generate Makefile:
+<nowiki>cmake -DCMAKE_TOOLCHAIN_FILE=<path_to_stm32.cmake> -DCMAKE_BUILD_TYPE=Debug <path_to_source_dir></nowiki>
+Build:
+<nowiki>make</nowiki>
+The result is a .elf, .bin, and hex files.
+For using with Eclipse CDT:
+<nowiki>cmake -DCMAKE_TOOLCHAIN_FILE=<path_to_stm32.cmake> -DCMAKE_BUILD_TYPE=Debug -G "Eclipse CDT4 - Unix Makefiles" <path_to_source_dir></nowiki>
+For release build:
+<nowiki>cmake -DCMAKE_TOOLCHAIN_FILE=<path_to_stm32.cmake> -DCMAKE_BUILD_TYPE=Release <path_to_source_dir></nowiki>

+ 74 - 0
stm32-blinky/CMakeLists.txt

@@ -0,0 +1,74 @@
+# Project name
+PROJECT(stm32-blinky)
+
+CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
+ENABLE_LANGUAGE(ASM)
+
+# Select your memory sizes here
+# Flash size
+SET(STM32_FLASH_SIZE "512K")
+# RAM size
+SET(STM32_RAM_SIZE "64K")
+# Stack address - bottom of RAM => RAM origin + RAM size
+SET(STM32_STACK_ADDRESS "0x20010000")
+
+# Origins
+SET(STM32_FLASH_ORIGIN "0x08000000")
+SET(STM32_RAM_ORIGIN "0x20000000")
+
+# Compiler definitions for std. periph. library
+# Select your chip type here
+SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DSTM32F10X_HD")
+SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSTM32F10X_HD")
+
+# Startup sources
+# Select your chip type here
+SET(STARTUP_SOURCE ${STM32_STARTUP_HD})
+
+# Uncomment needed modules
+SET(MOD_SOURCES
+  ${STM32_MISC_SOURCE}
+#  ${STM32_ADC_SOURCE}
+#  ${STM32_BKP_SOURCE}
+#  ${STM32_CAN_SOURCE}
+#  ${STM32_CEC_SOURCE}
+#  ${STM32_CRC_SOURCE}
+#  ${STM32_DAC_SOURCE}
+#  ${STM32_DBGMCU_SOURCE}
+#  ${STM32_DMA_SOURCE}
+#  ${STM32_EXTI_SOURCE}
+#  ${STM32_FLASH_SOURCE}
+#  ${STM32_FSMC_SOURCE}
+  ${STM32_GPIO_SOURCE}
+#  ${STM32_I2C_SOURCE}
+#  ${STM32_IWDG_SOURCE}
+#  ${STM32_PWR_SOURCE}
+  ${STM32_RCC_SOURCE}
+#  ${STM32_RTC_SOURCE}
+#  ${STM32_SDIO_SOURCE}
+#  ${STM32_SPI_SOURCE}
+  ${STM32_TIM_SOURCE}
+#  ${STM32_USART_SOURCE}
+#  ${STM32_WWDG_SOURCE}
+)
+
+# Project sources
+SET(PROJECT_SOURCES
+  main.c
+)
+
+# Configuring linker script for our target
+CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/stm32_flash.ld.in ${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld)
+SET(CMAKE_EXE_LINKER_FLAGS "-T${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld ${CMAKE_EXE_LINKER_FLAGS}")
+
+INCLUDE_DIRECTORIES(
+  ${CMAKE_CURRENT_SOURCE_DIR}/.
+  ${STM32_StdPeriphLib_INCLUDE_DIRS}
+)
+
+# Compile executable (*.elf)
+ADD_EXECUTABLE(${CMAKE_PROJECT_NAME}.elf ${PROJECT_SOURCES} ${MOD_SOURCES} ${STARTUP_SOURCE} ${STM32_SYSTEM_SOURCE})
+
+# Convert elf to bin and hex
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Oihex ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.hex)
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Obinary ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.bin)

+ 52 - 0
stm32-blinky/main.c

@@ -0,0 +1,52 @@
+#include <stm32f10x.h>
+
+void initGPIO()
+{
+    RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
+
+    GPIO_InitTypeDef GPIO_Config;
+    GPIO_Config.GPIO_Pin =  GPIO_Pin_6;
+    GPIO_Config.GPIO_Mode = GPIO_Mode_AF_PP;
+    GPIO_Config.GPIO_Speed = GPIO_Speed_50MHz;
+    GPIO_Init(GPIOA, &GPIO_Config);
+}
+
+void initTimers()
+{
+    TIM_TimeBaseInitTypeDef TIM_BaseConfig;
+    TIM_OCInitTypeDef TIM_OCConfig;
+
+    // 0 kHz timer.
+    TIM_BaseConfig.TIM_Prescaler = (uint16_t)(SystemCoreClock / 10000) - 1;
+    // 10000 / 5000 = 2 Hz blinking.
+    TIM_BaseConfig.TIM_Period = 5000;
+    TIM_BaseConfig.TIM_ClockDivision = 0;
+    TIM_BaseConfig.TIM_CounterMode = TIM_CounterMode_Up;
+    TIM_TimeBaseInit(TIM3, &TIM_BaseConfig);
+
+    TIM_OCConfig.TIM_OCMode = TIM_OCMode_PWM1;
+    TIM_OCConfig.TIM_OutputState = TIM_OutputState_Enable;
+    // 2500 / 5000 = 50% duty cycle.
+    TIM_OCConfig.TIM_Pulse = 2499;
+    TIM_OCConfig.TIM_OCPolarity = TIM_OCPolarity_High;
+    TIM_OC1Init(TIM3, &TIM_OCConfig);
+
+    TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
+    TIM_ARRPreloadConfig(TIM3, ENABLE);
+
+    TIM_Cmd(TIM3, ENABLE);
+}
+
+void initAll(void)
+{
+    initGPIO();
+    initTimers();
+}
+
+int main(void)
+{
+    initAll();
+    for (;;);
+    return 0;
+}

+ 152 - 0
stm32-blinky/stm32_flash.ld.in

@@ -0,0 +1,152 @@
+/*
+*****************************************************************************
+**
+**  Linker script for STM32F10x devices
+**
+**  Set heap size, stack size and stack location according
+**    to application requirements.
+**
+**  Set memory bank area and size if external memory is used.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ${STM32_STACK_ADDRESS};    /* end of RAM */
+
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0;      /* required amount of heap  */
+_Min_Stack_Size = 0x200; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+  FLASH (rx)      : ORIGIN = ${STM32_FLASH_ORIGIN}, LENGTH = ${STM32_FLASH_SIZE}
+  RAM (xrw)       : ORIGIN = ${STM32_RAM_ORIGIN}, LENGTH = ${STM32_RAM_SIZE}
+  MEMORY_B1 (rx)  : ORIGIN = 0x60000000, LENGTH = 0K
+}
+
+/* Define output sections */
+SECTIONS
+{
+  /* The startup code goes first into FLASH */
+  .isr_vector :
+  {
+    . = ALIGN(4);
+    KEEP(*(.isr_vector)) /* Startup code */
+    . = ALIGN(4);
+  } >FLASH
+
+  /* The program code and other data goes into FLASH */
+  .text :
+  {
+    . = ALIGN(4);
+    *(.text)           /* .text sections (code) */
+    *(.text*)          /* .text* sections (code) */
+    *(.rodata)         /* .rodata sections (constants, strings, etc.) */
+    *(.rodata*)        /* .rodata* sections (constants, strings, etc.) */
+    *(.glue_7)         /* glue arm to thumb code */
+    *(.glue_7t)        /* glue thumb to arm code */
+
+    KEEP (*(.init))
+    KEEP (*(.fini))
+
+    . = ALIGN(4);
+    _etext = .;        /* define a global symbols at end of code */
+  } >FLASH
+
+
+   .ARM.extab   : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+    .ARM : {
+    __exidx_start = .;
+      *(.ARM.exidx*)
+      __exidx_end = .;
+    } >FLASH
+
+  .ARM.attributes : { *(.ARM.attributes) } > FLASH
+
+  .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 (*(.fini_array*))
+    KEEP (*(SORT(.fini_array.*)))
+    PROVIDE_HIDDEN (__fini_array_end = .);
+  } >FLASH
+
+  /* used by the startup to initialize data */
+  _sidata = .;
+
+  /* Initialized data sections goes into RAM, load LMA copy after code */
+  .data : AT ( _sidata )
+  {
+    . = ALIGN(4);
+    _sdata = .;        /* create a global symbol at data start */
+    *(.data)           /* .data sections */
+    *(.data*)          /* .data* sections */
+
+    . = ALIGN(4);
+    _edata = .;        /* define a global symbol at data end */
+  } >RAM
+
+  /* Uninitialized data section */
+  . = ALIGN(4);
+  .bss :
+  {
+    /* This is used by the startup in order to initialize the .bss secion */
+    _sbss = .;         /* define a global symbol at bss start */
+    __bss_start__ = _sbss;
+    *(.bss)
+    *(.bss*)
+    *(COMMON)
+
+    . = ALIGN(4);
+    _ebss = .;         /* define a global symbol at bss end */
+    __bss_end__ = _ebss;
+  } >RAM
+
+  PROVIDE ( end = _ebss );
+  PROVIDE ( _end = _ebss );
+
+  /* User_heap_stack section, used to check that there is enough RAM left */
+  ._user_heap_stack :
+  {
+    . = ALIGN(4);
+    . = . + _Min_Heap_Size;
+    . = . + _Min_Stack_Size;
+    . = ALIGN(4);
+  } >RAM
+
+  /* MEMORY_bank1 section, code must be located here explicitly            */
+  /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
+  .memory_b1_text :
+  {
+    *(.mb1text)        /* .mb1text sections (code) */
+    *(.mb1text*)       /* .mb1text* sections (code)  */
+    *(.mb1rodata)      /* read-only data (constants) */
+    *(.mb1rodata*)
+  } >MEMORY_B1
+
+  /* Remove information from the standard libraries */
+  /DISCARD/ :
+  {
+    libc.a ( * )
+    libm.a ( * )
+    libgcc.a ( * )
+  }
+}

+ 77 - 0
stm32-blinky/stm32f10x_conf.h

@@ -0,0 +1,77 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_conf.h 
+  * @author  MCD Application Team
+  * @version V3.5.0
+  * @date    08-April-2011
+  * @brief   Library configuration file.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */
+// #include "stm32f10x_adc.h"
+// #include "stm32f10x_bkp.h"
+// #include "stm32f10x_can.h"
+// #include "stm32f10x_cec.h"
+// #include "stm32f10x_crc.h"
+// #include "stm32f10x_dac.h"
+// #include "stm32f10x_dbgmcu.h"
+// #include "stm32f10x_dma.h"
+// #include "stm32f10x_exti.h"
+// #include "stm32f10x_flash.h"
+// #include "stm32f10x_fsmc.h"
+ #include "stm32f10x_gpio.h"
+// #include "stm32f10x_i2c.h"
+// #include "stm32f10x_iwdg.h"
+// #include "stm32f10x_pwr.h"
+ #include "stm32f10x_rcc.h"
+// #include "stm32f10x_rtc.h"
+// #include "stm32f10x_sdio.h"
+// #include "stm32f10x_spi.h"
+ #include "stm32f10x_tim.h"
+// #include "stm32f10x_usart.h"
+// #include "stm32f10x_wwdg.h"
+ #include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to expanse the "assert_param" macro in the 
+   Standard Peripheral Library drivers code */
+/* #define USE_FULL_ASSERT    1 */
+
+/* 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)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+  void assert_failed(uint8_t* file, uint32_t line);
+#else
+  #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

+ 75 - 0
stm32-newlib/CMakeLists.txt

@@ -0,0 +1,75 @@
+# Project name
+PROJECT(stm32-newlib)
+
+CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
+ENABLE_LANGUAGE(ASM)
+
+# Select your memory sizes here
+# Flash size
+SET(STM32_FLASH_SIZE "512K")
+# RAM size
+SET(STM32_RAM_SIZE "64K")
+# Stack address - bottom of RAM => RAM origin + RAM size
+SET(STM32_STACK_ADDRESS "0x20010000")
+
+# Origins
+SET(STM32_FLASH_ORIGIN "0x08000000")
+SET(STM32_RAM_ORIGIN "0x20000000")
+
+# Compiler definitions for std. periph. library
+# Select your chip type here
+SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DSTM32F10X_HD")
+SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSTM32F10X_HD")
+
+# Startup sources
+# Select your chip type here
+SET(STARTUP_SOURCE ${STM32_STARTUP_HD})
+
+# Uncomment needed modules
+SET(MOD_SOURCES
+  ${STM32_MISC_SOURCE}
+#  ${STM32_ADC_SOURCE}
+  ${STM32_BKP_SOURCE}
+#  ${STM32_CAN_SOURCE}
+#  ${STM32_CEC_SOURCE}
+#  ${STM32_CRC_SOURCE}
+#  ${STM32_DAC_SOURCE}
+#  ${STM32_DBGMCU_SOURCE}
+#  ${STM32_DMA_SOURCE}
+#  ${STM32_EXTI_SOURCE}
+#  ${STM32_FLASH_SOURCE}
+#  ${STM32_FSMC_SOURCE}
+  ${STM32_GPIO_SOURCE}
+#  ${STM32_I2C_SOURCE}
+#  ${STM32_IWDG_SOURCE}
+  ${STM32_PWR_SOURCE}
+  ${STM32_RCC_SOURCE}
+  ${STM32_RTC_SOURCE}
+#  ${STM32_SDIO_SOURCE}
+#  ${STM32_SPI_SOURCE}
+#  ${STM32_TIM_SOURCE}
+  ${STM32_USART_SOURCE}
+#  ${STM32_WWDG_SOURCE}
+)
+
+# Project sources
+SET(PROJECT_SOURCES
+  main.c
+  newlib.c
+)
+
+# Configuring linker script for our target
+CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/stm32_flash.ld.in ${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld)
+SET(CMAKE_EXE_LINKER_FLAGS "-T${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld ${CMAKE_EXE_LINKER_FLAGS}")
+
+INCLUDE_DIRECTORIES(
+  ${CMAKE_CURRENT_SOURCE_DIR}/.
+  ${STM32_StdPeriphLib_INCLUDE_DIRS}
+)
+
+# Compile executable (*.elf)
+ADD_EXECUTABLE(${CMAKE_PROJECT_NAME}.elf ${PROJECT_SOURCES} ${MOD_SOURCES} ${STARTUP_SOURCE} ${STM32_SYSTEM_SOURCE})
+
+# Convert elf to bin and hex
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Oihex ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.hex)
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Obinary ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.bin)

+ 107 - 0
stm32-newlib/main.c

@@ -0,0 +1,107 @@
+#include <stm32f10x.h>
+#include <stdio.h>
+#include <time.h>
+
+void initGPIO()
+{
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
+    GPIO_InitTypeDef GPIO_Config;
+
+    /* USART1 Tx */
+    GPIO_Config.GPIO_Pin = GPIO_Pin_9;
+    GPIO_Config.GPIO_Mode = GPIO_Mode_AF_PP;
+    GPIO_Config.GPIO_Speed = GPIO_Speed_50MHz;
+    GPIO_Init(GPIOA, &GPIO_Config);
+
+    /* USART1 Rx */
+    GPIO_Config.GPIO_Pin = GPIO_Pin_10;
+    GPIO_Config.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+    GPIO_Config.GPIO_Speed = GPIO_Speed_50MHz;
+    GPIO_Init(GPIOA, &GPIO_Config);
+}
+
+void initRTC()
+{
+    RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+    if (BKP_ReadBackupRegister(BKP_DR1) != 0xA5A5)
+    {
+        PWR_BackupAccessCmd(ENABLE);
+
+        BKP_DeInit();
+        RCC_LSEConfig(RCC_LSE_ON);
+
+        while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET);
+
+        RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+        RCC_RTCCLKCmd(ENABLE);
+        RTC_WaitForSynchro();
+        RTC_WaitForLastTask();
+
+        RTC_SetPrescaler(32767);
+        RTC_WaitForLastTask();
+
+        BKP_WriteBackupRegister(BKP_DR1, 0xA5A5);
+        PWR_BackupAccessCmd(DISABLE);
+    }
+    RTC_WaitForSynchro();
+    RTC_WaitForLastTask();
+}
+
+void initUSART()
+{
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
+    USART_InitTypeDef USART_InitStructure;
+    USART_InitStructure.USART_BaudRate = 115200;
+    USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+    USART_InitStructure.USART_StopBits = USART_StopBits_1;
+    USART_InitStructure.USART_Parity = USART_Parity_No;
+    USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+    USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+    USART_Init(USART1, &USART_InitStructure);
+
+    USART_Cmd(USART1, ENABLE);
+}
+
+void setTime(uint32_t time)
+{
+    PWR_BackupAccessCmd(ENABLE);
+    RTC_WaitForLastTask();
+    RTC_SetCounter(time);
+    RTC_WaitForLastTask();
+    PWR_BackupAccessCmd(DISABLE);
+}
+
+void initAll(void)
+{
+    initRTC();
+    initGPIO();
+    initUSART();
+    RCC_ClearFlag();
+}
+
+int main(void)
+{
+    initAll();
+    for (;;)
+    {
+        char c;
+        time_t t;
+        scanf("%c", &c);
+        switch (c)
+        {
+        case 's':
+            scanf("%d", &t);
+            setTime(t);
+            printf("Current time changed: %d - %s\r", t, ctime(&t));
+            break;
+        default:
+            RTC_WaitForLastTask();
+            t = time(0);
+            printf("Current time: %d - %s\r", t, ctime(&t));
+            break;
+        }
+    }
+    return 0;
+}

+ 183 - 0
stm32-newlib/newlib.c

@@ -0,0 +1,183 @@
+#include <errno.h>
+#include <sys/stat.h>
+#include <sys/times.h>
+#include <sys/unistd.h>
+#include <sys/time.h>
+#include <stm32f10x.h>
+
+extern uint32_t __get_MSP(void);
+
+#define STDOUT_USART USART1
+#define STDERR_USART USART1
+#define STDIN_USART USART1
+
+#undef errno
+extern int errno;
+
+char *__env[1] = { 0 };
+char **environ = __env;
+
+int _write(int file, char *ptr, int len);
+
+void _exit(int status)
+{
+    while (1);
+}
+
+int _close(int file)
+{
+    return -1;
+}
+
+int _execve(char *name, char **argv, char **env)
+{
+    errno = ENOMEM;
+    return -1;
+}
+
+int _fork()
+{
+    errno = EAGAIN;
+    return -1;
+}
+
+int _fstat(int file, struct stat *st)
+{
+    st->st_mode = S_IFCHR;
+    return 0;
+}
+
+int _getpid()
+{
+    return 1;
+}
+
+int _gettimeofday(struct timeval *tv, struct timezone *tz)
+{
+    tv->tv_sec = RTC_GetCounter();
+    tv->tv_usec = 0;
+    return 0;
+}
+
+int _isatty(int file)
+{
+    switch (file)
+    {
+    case STDOUT_FILENO:
+    case STDERR_FILENO:
+    case STDIN_FILENO:
+        return 1;
+    default:
+        //errno = ENOTTY;
+        errno = EBADF;
+        return 0;
+    }
+}
+
+int _kill(int pid, int sig)
+{
+    errno = EINVAL;
+    return (-1);
+}
+
+int _link(char *old, char *new)
+{
+    errno = EMLINK;
+    return -1;
+}
+
+int _lseek(int file, int ptr, int dir)
+{
+    return 0;
+}
+
+caddr_t _sbrk(int incr)
+{
+    extern char _ebss;
+    static char *heap_end;
+    char *prev_heap_end;
+
+    if (heap_end == 0)
+    {
+        heap_end = &_ebss;
+    }
+    prev_heap_end = heap_end;
+
+    char * stack = (char*) __get_MSP();
+    if (heap_end + incr > stack)
+    {
+        _write(STDERR_FILENO, "Heap and stack collision\n", 25);
+        errno = ENOMEM;
+        return (caddr_t) - 1;
+        //abort ();
+    }
+
+    heap_end += incr;
+    return (caddr_t) prev_heap_end;
+
+}
+
+int _read(int file, char *ptr, int len)
+{
+    switch (file)
+    {
+    case STDIN_FILENO:
+        while (USART_GetFlagStatus(STDIN_USART, USART_FLAG_RXNE) == RESET);
+        char c = (char)(USART_ReceiveData(STDIN_USART) & (uint16_t) 0x01FF);
+        *ptr++ = c;
+        return 1;
+        break;
+    default:
+        errno = EBADF;
+        return -1;
+    }
+}
+
+int _stat(const char *filepath, struct stat *st)
+{
+    st->st_mode = S_IFCHR;
+    return 0;
+}
+
+clock_t _times(struct tms *buf)
+{
+    return -1;
+}
+
+int _unlink(char *name)
+{
+    errno = ENOENT;
+    return -1;
+}
+
+int _wait(int *status)
+{
+    errno = ECHILD;
+    return -1;
+}
+
+int _write(int file, char *ptr, int len)
+{
+    int n;
+    switch (file)
+    {
+    case STDOUT_FILENO: /*stdout*/
+        for (n = 0; n < len; n++)
+        {
+            while (USART_GetFlagStatus(STDOUT_USART, USART_FLAG_TC) == RESET);
+            USART_SendData(STDOUT_USART, (uint8_t) * ptr++);
+        }
+        break;
+    case STDERR_FILENO: /* stderr */
+        for (n = 0; n < len; n++)
+        {
+            while (USART_GetFlagStatus(STDERR_USART, USART_FLAG_TC) == RESET);
+            USART_SendData(STDERR_USART, (uint8_t) * ptr++);
+        }
+        break;
+    default:
+        errno = EBADF;
+        return -1;
+    }
+    return len;
+}

+ 152 - 0
stm32-newlib/stm32_flash.ld.in

@@ -0,0 +1,152 @@
+/*
+*****************************************************************************
+**
+**  Linker script for STM32F10x devices
+**
+**  Set heap size, stack size and stack location according
+**    to application requirements.
+**
+**  Set memory bank area and size if external memory is used.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ${STM32_STACK_ADDRESS};    /* end of RAM */
+
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0;      /* required amount of heap  */
+_Min_Stack_Size = 0x200; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+  FLASH (rx)      : ORIGIN = ${STM32_FLASH_ORIGIN}, LENGTH = ${STM32_FLASH_SIZE}
+  RAM (xrw)       : ORIGIN = ${STM32_RAM_ORIGIN}, LENGTH = ${STM32_RAM_SIZE}
+  MEMORY_B1 (rx)  : ORIGIN = 0x60000000, LENGTH = 0K
+}
+
+/* Define output sections */
+SECTIONS
+{
+  /* The startup code goes first into FLASH */
+  .isr_vector :
+  {
+    . = ALIGN(4);
+    KEEP(*(.isr_vector)) /* Startup code */
+    . = ALIGN(4);
+  } >FLASH
+
+  /* The program code and other data goes into FLASH */
+  .text :
+  {
+    . = ALIGN(4);
+    *(.text)           /* .text sections (code) */
+    *(.text*)          /* .text* sections (code) */
+    *(.rodata)         /* .rodata sections (constants, strings, etc.) */
+    *(.rodata*)        /* .rodata* sections (constants, strings, etc.) */
+    *(.glue_7)         /* glue arm to thumb code */
+    *(.glue_7t)        /* glue thumb to arm code */
+
+    KEEP (*(.init))
+    KEEP (*(.fini))
+
+    . = ALIGN(4);
+    _etext = .;        /* define a global symbols at end of code */
+  } >FLASH
+
+
+   .ARM.extab   : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+    .ARM : {
+    __exidx_start = .;
+      *(.ARM.exidx*)
+      __exidx_end = .;
+    } >FLASH
+
+  .ARM.attributes : { *(.ARM.attributes) } > FLASH
+
+  .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 (*(.fini_array*))
+    KEEP (*(SORT(.fini_array.*)))
+    PROVIDE_HIDDEN (__fini_array_end = .);
+  } >FLASH
+
+  /* used by the startup to initialize data */
+  _sidata = .;
+
+  /* Initialized data sections goes into RAM, load LMA copy after code */
+  .data : AT ( _sidata )
+  {
+    . = ALIGN(4);
+    _sdata = .;        /* create a global symbol at data start */
+    *(.data)           /* .data sections */
+    *(.data*)          /* .data* sections */
+
+    . = ALIGN(4);
+    _edata = .;        /* define a global symbol at data end */
+  } >RAM
+
+  /* Uninitialized data section */
+  . = ALIGN(4);
+  .bss :
+  {
+    /* This is used by the startup in order to initialize the .bss secion */
+    _sbss = .;         /* define a global symbol at bss start */
+    __bss_start__ = _sbss;
+    *(.bss)
+    *(.bss*)
+    *(COMMON)
+
+    . = ALIGN(4);
+    _ebss = .;         /* define a global symbol at bss end */
+    __bss_end__ = _ebss;
+  } >RAM
+
+  PROVIDE ( end = _ebss );
+  PROVIDE ( _end = _ebss );
+
+  /* User_heap_stack section, used to check that there is enough RAM left */
+  ._user_heap_stack :
+  {
+    . = ALIGN(4);
+    . = . + _Min_Heap_Size;
+    . = . + _Min_Stack_Size;
+    . = ALIGN(4);
+  } >RAM
+
+  /* MEMORY_bank1 section, code must be located here explicitly            */
+  /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
+  .memory_b1_text :
+  {
+    *(.mb1text)        /* .mb1text sections (code) */
+    *(.mb1text*)       /* .mb1text* sections (code)  */
+    *(.mb1rodata)      /* read-only data (constants) */
+    *(.mb1rodata*)
+  } >MEMORY_B1
+
+  /* Remove information from the standard libraries */
+  /DISCARD/ :
+  {
+    libc.a ( * )
+    libm.a ( * )
+    libgcc.a ( * )
+  }
+}

+ 77 - 0
stm32-newlib/stm32f10x_conf.h

@@ -0,0 +1,77 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_conf.h 
+  * @author  MCD Application Team
+  * @version V3.5.0
+  * @date    08-April-2011
+  * @brief   Library configuration file.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */
+// #include "stm32f10x_adc.h"
+ #include "stm32f10x_bkp.h"
+// #include "stm32f10x_can.h"
+// #include "stm32f10x_cec.h"
+// #include "stm32f10x_crc.h"
+// #include "stm32f10x_dac.h"
+// #include "stm32f10x_dbgmcu.h"
+// #include "stm32f10x_dma.h"
+// #include "stm32f10x_exti.h"
+// #include "stm32f10x_flash.h"
+// #include "stm32f10x_fsmc.h"
+ #include "stm32f10x_gpio.h"
+// #include "stm32f10x_i2c.h"
+// #include "stm32f10x_iwdg.h"
+ #include "stm32f10x_pwr.h"
+ #include "stm32f10x_rcc.h"
+ #include "stm32f10x_rtc.h"
+// #include "stm32f10x_sdio.h"
+// #include "stm32f10x_spi.h"
+// #include "stm32f10x_tim.h"
+ #include "stm32f10x_usart.h"
+// #include "stm32f10x_wwdg.h"
+ #include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to expanse the "assert_param" macro in the 
+   Standard Peripheral Library drivers code */
+/* #define USE_FULL_ASSERT    1 */
+
+/* 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)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+  void assert_failed(uint8_t* file, uint32_t line);
+#else
+  #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

+ 74 - 0
stm32-template/CMakeLists.txt

@@ -0,0 +1,74 @@
+# Project name
+PROJECT(stm32-template)
+
+CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
+ENABLE_LANGUAGE(ASM)
+
+# Select your memory sizes here
+# Flash size
+SET(STM32_FLASH_SIZE "512K")
+# RAM size
+SET(STM32_RAM_SIZE "64K")
+# Stack address - bottom of RAM => RAM origin + RAM size
+SET(STM32_STACK_ADDRESS "0x20010000")
+
+# Origins
+SET(STM32_FLASH_ORIGIN "0x08000000")
+SET(STM32_RAM_ORIGIN "0x20000000")
+
+# Compiler definitions for std. periph. library
+# Select your chip type here
+SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DSTM32F10X_HD")
+SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSTM32F10X_HD")
+
+# Startup sources
+# Select your chip type here
+SET(STARTUP_SOURCE ${STM32_STARTUP_HD})
+
+# Uncomment needed modules
+SET(MOD_SOURCES
+  ${STM32_MISC_SOURCE}
+#  ${STM32_ADC_SOURCE}
+#  ${STM32_BKP_SOURCE}
+#  ${STM32_CAN_SOURCE}
+#  ${STM32_CEC_SOURCE}
+#  ${STM32_CRC_SOURCE}
+#  ${STM32_DAC_SOURCE}
+#  ${STM32_DBGMCU_SOURCE}
+#  ${STM32_DMA_SOURCE}
+#  ${STM32_EXTI_SOURCE}
+#  ${STM32_FLASH_SOURCE}
+#  ${STM32_FSMC_SOURCE}
+  ${STM32_GPIO_SOURCE}
+#  ${STM32_I2C_SOURCE}
+#  ${STM32_IWDG_SOURCE}
+#  ${STM32_PWR_SOURCE}
+  ${STM32_RCC_SOURCE}
+#  ${STM32_RTC_SOURCE}
+#  ${STM32_SDIO_SOURCE}
+#  ${STM32_SPI_SOURCE}
+  ${STM32_TIM_SOURCE}
+#  ${STM32_USART_SOURCE}
+#  ${STM32_WWDG_SOURCE}
+)
+
+# Project sources
+SET(PROJECT_SOURCES
+  main.c
+)
+
+# Configuring linker script for our target
+CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/stm32_flash.ld.in ${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld)
+SET(CMAKE_EXE_LINKER_FLAGS "-T${CMAKE_CURRENT_BINARY_DIR}/stm32_flash.ld ${CMAKE_EXE_LINKER_FLAGS}")
+
+INCLUDE_DIRECTORIES(
+  ${CMAKE_CURRENT_SOURCE_DIR}/.
+  ${STM32_StdPeriphLib_INCLUDE_DIRS}
+)
+
+# Compile executable (*.elf)
+ADD_EXECUTABLE(${CMAKE_PROJECT_NAME}.elf ${PROJECT_SOURCES} ${MOD_SOURCES} ${STARTUP_SOURCE} ${STM32_SYSTEM_SOURCE})
+
+# Convert elf to bin and hex
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Oihex ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.hex)
+ADD_CUSTOM_COMMAND(TARGET ${CMAKE_PROJECT_NAME}.elf POST_BUILD COMMAND ${CMAKE_OBJCOPY} ARGS -Obinary ${CMAKE_PROJECT_NAME}.elf ${CMAKE_PROJECT_NAME}.bin)

+ 7 - 0
stm32-template/main.c

@@ -0,0 +1,7 @@
+#include <stm32f10x.h>
+
+int main(void)
+{
+    for (;;);
+    return 0;
+}

+ 152 - 0
stm32-template/stm32_flash.ld.in

@@ -0,0 +1,152 @@
+/*
+*****************************************************************************
+**
+**  Linker script for STM32F10x devices
+**
+**  Set heap size, stack size and stack location according
+**    to application requirements.
+**
+**  Set memory bank area and size if external memory is used.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ${STM32_STACK_ADDRESS};    /* end of RAM */
+
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0;      /* required amount of heap  */
+_Min_Stack_Size = 0x200; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+  FLASH (rx)      : ORIGIN = ${STM32_FLASH_ORIGIN}, LENGTH = ${STM32_FLASH_SIZE}
+  RAM (xrw)       : ORIGIN = ${STM32_RAM_ORIGIN}, LENGTH = ${STM32_RAM_SIZE}
+  MEMORY_B1 (rx)  : ORIGIN = 0x60000000, LENGTH = 0K
+}
+
+/* Define output sections */
+SECTIONS
+{
+  /* The startup code goes first into FLASH */
+  .isr_vector :
+  {
+    . = ALIGN(4);
+    KEEP(*(.isr_vector)) /* Startup code */
+    . = ALIGN(4);
+  } >FLASH
+
+  /* The program code and other data goes into FLASH */
+  .text :
+  {
+    . = ALIGN(4);
+    *(.text)           /* .text sections (code) */
+    *(.text*)          /* .text* sections (code) */
+    *(.rodata)         /* .rodata sections (constants, strings, etc.) */
+    *(.rodata*)        /* .rodata* sections (constants, strings, etc.) */
+    *(.glue_7)         /* glue arm to thumb code */
+    *(.glue_7t)        /* glue thumb to arm code */
+
+    KEEP (*(.init))
+    KEEP (*(.fini))
+
+    . = ALIGN(4);
+    _etext = .;        /* define a global symbols at end of code */
+  } >FLASH
+
+
+   .ARM.extab   : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+    .ARM : {
+    __exidx_start = .;
+      *(.ARM.exidx*)
+      __exidx_end = .;
+    } >FLASH
+
+  .ARM.attributes : { *(.ARM.attributes) } > FLASH
+
+  .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 (*(.fini_array*))
+    KEEP (*(SORT(.fini_array.*)))
+    PROVIDE_HIDDEN (__fini_array_end = .);
+  } >FLASH
+
+  /* used by the startup to initialize data */
+  _sidata = .;
+
+  /* Initialized data sections goes into RAM, load LMA copy after code */
+  .data : AT ( _sidata )
+  {
+    . = ALIGN(4);
+    _sdata = .;        /* create a global symbol at data start */
+    *(.data)           /* .data sections */
+    *(.data*)          /* .data* sections */
+
+    . = ALIGN(4);
+    _edata = .;        /* define a global symbol at data end */
+  } >RAM
+
+  /* Uninitialized data section */
+  . = ALIGN(4);
+  .bss :
+  {
+    /* This is used by the startup in order to initialize the .bss secion */
+    _sbss = .;         /* define a global symbol at bss start */
+    __bss_start__ = _sbss;
+    *(.bss)
+    *(.bss*)
+    *(COMMON)
+
+    . = ALIGN(4);
+    _ebss = .;         /* define a global symbol at bss end */
+    __bss_end__ = _ebss;
+  } >RAM
+
+  PROVIDE ( end = _ebss );
+  PROVIDE ( _end = _ebss );
+
+  /* User_heap_stack section, used to check that there is enough RAM left */
+  ._user_heap_stack :
+  {
+    . = ALIGN(4);
+    . = . + _Min_Heap_Size;
+    . = . + _Min_Stack_Size;
+    . = ALIGN(4);
+  } >RAM
+
+  /* MEMORY_bank1 section, code must be located here explicitly            */
+  /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
+  .memory_b1_text :
+  {
+    *(.mb1text)        /* .mb1text sections (code) */
+    *(.mb1text*)       /* .mb1text* sections (code)  */
+    *(.mb1rodata)      /* read-only data (constants) */
+    *(.mb1rodata*)
+  } >MEMORY_B1
+
+  /* Remove information from the standard libraries */
+  /DISCARD/ :
+  {
+    libc.a ( * )
+    libm.a ( * )
+    libgcc.a ( * )
+  }
+}

+ 77 - 0
stm32-template/stm32f10x_conf.h

@@ -0,0 +1,77 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_conf.h 
+  * @author  MCD Application Team
+  * @version V3.5.0
+  * @date    08-April-2011
+  * @brief   Library configuration file.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */
+// #include "stm32f10x_adc.h"
+// #include "stm32f10x_bkp.h"
+// #include "stm32f10x_can.h"
+// #include "stm32f10x_cec.h"
+// #include "stm32f10x_crc.h"
+// #include "stm32f10x_dac.h"
+// #include "stm32f10x_dbgmcu.h"
+// #include "stm32f10x_dma.h"
+// #include "stm32f10x_exti.h"
+// #include "stm32f10x_flash.h"
+// #include "stm32f10x_fsmc.h"
+// #include "stm32f10x_gpio.h"
+// #include "stm32f10x_i2c.h"
+// #include "stm32f10x_iwdg.h"
+// #include "stm32f10x_pwr.h"
+// #include "stm32f10x_rcc.h"
+// #include "stm32f10x_rtc.h"
+// #include "stm32f10x_sdio.h"
+// #include "stm32f10x_spi.h"
+// #include "stm32f10x_tim.h"
+// #include "stm32f10x_usart.h"
+// #include "stm32f10x_wwdg.h"
+// #include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to expanse the "assert_param" macro in the 
+   Standard Peripheral Library drivers code */
+/* #define USE_FULL_ASSERT    1 */
+
+/* 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)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+  void assert_failed(uint8_t* file, uint32_t line);
+#else
+  #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

+ 102 - 0
stm32.cmake

@@ -0,0 +1,102 @@
+# CodeSourcery toolchain prefix
+IF(NOT TOOLCHAIN_PREFIX)
+    SET(TOOLCHAIN_PREFIX "/usr")
+    MESSAGE(STATUS "No TOOLCHAIN_PREFIX specified, using default: " ${TOOLCHAIN_PREFIX})
+ENDIF()
+
+
+# STM Library directory
+IF(NOT STM32_StdPeriphLib_DIR)
+    SET(STM32_StdPeriphLib_DIR "/opt/STM32F10x_StdPeriph_Lib_V3.5.0")
+    MESSAGE(STATUS "No STM32_StdPeriphLib_DIR specified, using default: " ${STM32_StdPeriphLib_DIR})
+ENDIF()
+
+IF(NOT TARGET_TRIPLET)
+    SET(TARGET_TRIPLET "arm-none-eabi")
+    MESSAGE(STATUS "No TARGET_TRIPLET specified, using default: " ${TARGET_TRIPLET})
+ENDIF()
+
+SET(STM32_StdPeriphLib_INCLUDE_DIRS 
+    ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/inc/
+    ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/
+    ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/CoreSupport/
+)
+
+SET(TOOLCHAIN_BIN_DIR ${TOOLCHAIN_PREFIX}/bin)
+SET(TOOLCHAIN_LIBC_DIR ${TOOLCHAIN_PREFIX}/${TARGET_TRIPLET}/libc)
+SET(TOOLCHAIN_INC_DIR ${TOOLCHAIN_LIBC_DIR}/include)
+SET(TOOLCHAIN_LIB_DIR ${TOOLCHAIN_LIBC_DIR}/usr/lib)
+
+SET(CMAKE_SYSTEM_NAME Linux CACHE INTERNAL "system name")
+SET(CMAKE_SYSTEM_PROCESSOR arm CACHE INTERNAL "processor")
+
+SET(CMAKE_C_COMPILER ${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc CACHE INTERNAL "")
+SET(CMAKE_CXX_COMPILER ${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-g++ CACHE INTERNAL "")
+SET(CMAKE_ASM_COMPILER ${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-as CACHE INTERNAL "")
+
+SET(CMAKE_OBJCOPY ${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objcopy CACHE INTERNAL "")
+SET(CMAKE_OBJDUMP ${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objdump CACHE INTERNAL "")
+
+SET(CMAKE_C_FLAGS "-isystem ${TOOLCHAIN_INC_DIR} -mthumb -mcpu=cortex-m3 -fno-builtin -Wall -std=gnu99 -fdata-sections -ffunction-sections -DUSE_STDPERIPH_DRIVER" CACHE INTERNAL "c compiler flags")
+SET(CMAKE_CXX_FLAGS "-isystem ${TOOLCHAIN_INC_DIR} -mthumb -mcpu=cortex-m3 -fno-builtin -Wall  -fdata-sections -ffunction-sections -DUSE_STDPERIPH_DRIVER" CACHE INTERNAL "cxx compiler flags")
+SET(CMAKE_ASM_FLAGS "-mthumb -mcpu=cortex-m3" CACHE INTERNAL "asm compiler flags")
+
+SET(CMAKE_C_FLAGS_DEBUG "-O0 -g -gstabs+" CACHE INTERNAL "c debug compiler flags")
+SET(CMAKE_CXX_FLAGS_DEBUG "-O0 -g -gstabs+" CACHE INTERNAL "cxx debug compiler flags")
+SET(CMAKE_ASM_FLAGS_DEBUG "-g -gstabs+" CACHE INTERNAL "asm debug compiler flags")
+
+SET(CMAKE_C_FLAGS_RELEASE "-Os" CACHE INTERNAL "c release compiler flags")
+SET(CMAKE_CXX_FLAGS_RELEASE "-Os" CACHE INTERNAL "cxx release compiler flags")
+SET(CMAKE_ASM_FLAGS_RELEASE "" CACHE INTERNAL "asm release compiler flags")
+
+SET(CMAKE_EXE_LINKER_FLAGS "-nostartfiles -Wl,-Map -Wl,main.map -Wl,--gc-sections -mthumb -mcpu=cortex-m3" CACHE INTERNAL "exe link flags")
+SET(CMAKE_MODULE_LINKER_FLAGS "-L${TOOLCHAIN_LIB_DIR}" CACHE INTERNAL "module link flags")
+SET(CMAKE_SHARED_LINKER_FLAGS "-L${TOOLCHAIN_LIB_DIR}" CACHE INTERNAL "shared lnk flags")
+set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "")
+set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")
+
+SET(CMAKE_FIND_ROOT_PATH ${TOOLCHAIN_LIBC_DIR} CACHE INTERNAL "cross root directory")
+SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM BOTH CACHE INTERNAL "")
+SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY CACHE INTERNAL "")
+SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY CACHE INTERNAL "")
+
+# Startup sources
+SET(STM32_STARTUP_CL ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s)
+SET(STM32_STARTUP_HD ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s)
+SET(STM32_STARTUP_HD_VL ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s)
+SET(STM32_STARTUP_LD ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s)
+SET(STM32_STARTUP_LD_VL ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s)
+SET(STM32_STARTUP_MD ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s)
+SET(STM32_STARTUP_MD_VL ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s)
+SET(STM32_STARTUP_XL ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s)
+
+# System source
+SET(STM32_SYSTEM_SOURCE 
+    ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c
+    ${STM32_StdPeriphLib_DIR}/Libraries/CMSIS/CM3/CoreSupport/core_cm3.c
+)
+
+SET(STM32_MISC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c)
+SET(STM32_ADC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c)
+SET(STM32_BKP_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c)
+SET(STM32_CAN_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c)
+SET(STM32_CEC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c)
+SET(STM32_CRC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c)
+SET(STM32_DAC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c)
+SET(STM32_DBGMCU_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c)
+SET(STM32_DMA_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c)
+SET(STM32_EXTI_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c)
+SET(STM32_FLASH_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c)
+SET(STM32_FSMC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c)
+SET(STM32_GPIO_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c)
+SET(STM32_I2C_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c)
+SET(STM32_IWDG_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c)
+SET(STM32_PWR_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c)
+SET(STM32_RCC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c)
+SET(STM32_RTC_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c)
+SET(STM32_SDIO_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c)
+SET(STM32_SPI_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c)
+SET(STM32_TIM_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c)
+SET(STM32_USART_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c)
+SET(STM32_WWDG_SOURCE ${STM32_StdPeriphLib_DIR}/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c)
+