Rename board specific demos as appropriate
authorKarl Palsson <karlp@tweak.net.au>
Mon, 7 Nov 2011 22:56:15 +0000 (22:56 +0000)
committerKarl Palsson <karlp@tweak.net.au>
Mon, 14 Nov 2011 02:47:44 +0000 (02:47 +0000)
12 files changed:
example/32l_dac/Makefile [new file with mode: 0644]
example/32l_dac/discover_board.h [new file with mode: 0644]
example/32l_dac/main.c [new file with mode: 0644]
example/32l_dac/startup_stm32l1xx_md.s [new file with mode: 0644]
example/32l_dac/stm32_flash.ld [new file with mode: 0644]
example/32l_dac/system_stm32l1xx.c [new file with mode: 0644]
example/dac/Makefile [deleted file]
example/dac/discover_board.h [deleted file]
example/dac/main.c [deleted file]
example/dac/startup_stm32l1xx_md.s [deleted file]
example/dac/stm32_flash.ld [deleted file]
example/dac/system_stm32l1xx.c [deleted file]

diff --git a/example/32l_dac/Makefile b/example/32l_dac/Makefile
new file mode 100644 (file)
index 0000000..84db69e
--- /dev/null
@@ -0,0 +1,43 @@
+EXECUTABLE=dac.elf
+BIN_IMAGE=dac.bin
+
+CC=arm-none-eabi-gcc
+OBJCOPY=arm-none-eabi-objcopy
+
+CFLAGS=-O3 -mlittle-endian -mthumb
+ifeq ($(CONFIG_STM32L_DISCOVERY), 1)
+       CFLAGS+=-mcpu=cortex-m3 -DCONFIG_STM32L_DISCOVERY=1
+else ifeq ($(CONFIG_STM32VL_DISCOVERY), 1)
+       CFLAGS+=-mcpu=cortex-m3 -DCONFIG_STM32VL_DISCOVERY=1
+else ifeq ($(CONFIG_STM32F4_DISCOVERY), 1)
+       CFLAGS+=-mcpu=cortex-m4 -DCONFIG_STM32F4_DISCOVERY=1    
+else
+$(error "must specify CONFIG_ for board!")
+endif
+CFLAGS+=-ffreestanding -nostdlib -nostdinc
+
+# to run from FLASH
+CFLAGS+=-Wl,-T,stm32_flash.ld
+
+# stm32l_discovery lib
+CFLAGS+=-I../libstm32l_discovery/inc
+CFLAGS+=-I../libstm32l_discovery/inc/base
+CFLAGS+=-I../libstm32l_discovery/inc/core_support
+CFLAGS+=-I../libstm32l_discovery/inc/device_support
+
+all: $(BIN_IMAGE)
+
+$(BIN_IMAGE): $(EXECUTABLE)
+       $(OBJCOPY) -O binary $^ $@
+
+$(EXECUTABLE): main.c system_stm32l1xx.c startup_stm32l1xx_md.s
+       $(CC) $(CFLAGS) $^ -o $@  -L../libstm32l_discovery/build -lstm32l_discovery
+
+clean:
+       rm -rf $(EXECUTABLE)
+       rm -rf $(BIN_IMAGE)
+
+write: all
+       sudo ../../flash/flash write ./dac.bin 0x08000000
+
+.PHONY: all clean write
diff --git a/example/32l_dac/discover_board.h b/example/32l_dac/discover_board.h
new file mode 100644 (file)
index 0000000..d93a184
--- /dev/null
@@ -0,0 +1,61 @@
+ /**\r
+  ******************************************************************************\r
+  * @file    discover_board.h\r
+  * @author  Microcontroller Division\r
+  * @version V1.0.2\r
+  * @date    September-2011\r
+  * @brief   Input/Output defines\r
+  ******************************************************************************\r
+  * @copy\r
+  *\r
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
+  *\r
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>\r
+  */\r
+\r
+/* Define to prevent recursive inclusion -------------------------------------*/\r
+\r
+#ifndef __DISCOVER_BOARD_H\r
+#define __DISCOVER_BOARD_H\r
+\r
+/* Includes ------------------------------------------------------------------*/\r
+/* #include "stm32l1xx.h"   */\r
+\r
+#define bool _Bool\r
+#define FALSE 0\r
+#define TRUE !FALSE\r
+\r
+/* MACROs for SET, RESET or TOGGLE Output port */\r
+\r
+#define GPIO_HIGH(a,b)                 a->BSRRL = b\r
+#define GPIO_LOW(a,b)          a->BSRRH = b\r
+#define GPIO_TOGGLE(a,b)       a->ODR ^= b \r
+\r
+#define USERBUTTON_GPIO_PORT   GPIOA\r
+#define USERBUTTON_GPIO_PIN     GPIO_Pin_0\r
+#define USERBUTTON_GPIO_CLK     RCC_AHBPeriph_GPIOA\r
+\r
+#define LD_GPIO_PORT           GPIOB\r
+#define LD_GREEN_GPIO_PIN              GPIO_Pin_7\r
+#define LD_BLUE_GPIO_PIN             GPIO_Pin_6\r
+#define LD_GPIO_PORT_CLK             RCC_AHBPeriph_GPIOB\r
+\r
+#define CTN_GPIO_PORT           GPIOC\r
+#define CTN_CNTEN_GPIO_PIN      GPIO_Pin_13\r
+#define CTN_GPIO_CLK            RCC_AHBPeriph_GPIOC\r
+\r
+#define WAKEUP_GPIO_PORT        GPIOA\r
+\r
+#define IDD_MEASURE_PORT       GPIOA\r
+#define IDD_MEASURE             GPIO_Pin_4\r
+\r
+\r
+#endif\r
+\r
+\r
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/\r
diff --git a/example/32l_dac/main.c b/example/32l_dac/main.c
new file mode 100644 (file)
index 0000000..1f89d33
--- /dev/null
@@ -0,0 +1,242 @@
+/* base headers */
+#include "stdint.h"
+
+/* libstm32l_discovery headers */
+#include "stm32l1xx_gpio.h"
+#include "stm32l1xx_adc.h"
+#include "stm32l1xx_dac.h"
+#include "stm32l1xx_lcd.h"
+#include "stm32l1xx_rcc.h"
+#include "stm32l1xx_rtc.h"
+#include "stm32l1xx_exti.h"
+#include "stm32l1xx_pwr.h"
+#include "stm32l1xx_flash.h"
+#include "stm32l1xx_syscfg.h"
+#include "stm32l1xx_dbgmcu.h"
+
+/* board specific macros */
+#include "discover_board.h"
+
+
+/* hardware configuration */
+
+#if CONFIG_STM32VL_DISCOVERY
+
+# define GPIOC 0x40011000 /* port C */
+# define GPIOC_CRH (GPIOC + 0x04) /* port configuration register high */
+# define GPIOC_ODR (GPIOC + 0x0c) /* port output data register */
+
+# define LED_BLUE (1 << 8) /* port C, pin 8 */
+# define LED_GREEN (1 << 9) /* port C, pin 9 */
+
+static inline void setup_leds(void)
+{
+  *(volatile uint32_t*)GPIOC_CRH = 0x44444411;
+}
+
+static inline void switch_leds_on(void)
+{
+  *(volatile uint32_t*)GPIOC_ODR = LED_BLUE | LED_GREEN;
+}
+
+static inline void switch_leds_off(void)
+{
+  *(volatile uint32_t*)GPIOC_ODR = 0;
+}
+
+#elif CONFIG_STM32L_DISCOVERY
+
+# define GPIOB_MODER (GPIOB + 0x00) /* port mode register */
+# define GPIOB_ODR (GPIOB + 0x14) /* port output data register */
+
+# define LED_BLUE (1 << 6) /* port B, pin 6 */
+# define LED_GREEN (1 << 7) /* port B, pin 7 */
+
+static inline void setup_leds(void)
+{
+  /* configure port 6 and 7 as output */
+  *(volatile uint32_t*)GPIOB_MODER |= (1 << (7 * 2)) | (1 << (6 * 2));
+}
+
+static inline void switch_leds_on(void)
+{
+  GPIO_HIGH(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);  
+  GPIO_HIGH(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
+}
+
+static inline void switch_leds_off(void)
+{
+  GPIO_LOW(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);   
+  GPIO_LOW(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
+}
+
+#endif /* otherwise, error */
+
+
+#define delay()                                                \
+do {                                                   \
+  volatile unsigned int i;                             \
+  for (i = 0; i < 1000000; ++i)                                \
+    __asm__ __volatile__ ("nop\n\t":::"memory");       \
+} while (0)
+
+
+static void RCC_Configuration(void)
+{
+  /* HSI is 16mhz RC clock directly fed to SYSCLK (rm00038, figure 9) */
+
+  /* enable the HSI clock (high speed internal) */
+  RCC_HSICmd(ENABLE);
+  
+  /* wail til HSI ready */
+  while (RCC_GetFlagStatus(RCC_FLAG_HSIRDY) == RESET)
+  {}
+
+  /* at startup, SYSCLK driven by MSI. set to HSI */
+  RCC_SYSCLKConfig(RCC_SYSCLKSource_HSI);
+  
+  /* set MSI to 4mhz */
+  RCC_MSIRangeConfig(RCC_MSIRange_6);
+
+  /* turn HSE off */
+  RCC_HSEConfig(RCC_HSE_OFF);  
+  if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+  {
+    while (1) ;
+  }
+}
+
+
+static void RTC_Configuration(void)
+{
+  /* Allow access to the RTC */
+  PWR_RTCAccessCmd(ENABLE);
+
+  /* Reset Backup Domain */
+  RCC_RTCResetCmd(ENABLE);
+  RCC_RTCResetCmd(DISABLE);
+
+  /* LSE Enable */
+  RCC_LSEConfig(RCC_LSE_ON);
+
+  /* Wait till LSE is ready */
+  while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
+  {}
+  
+  RCC_RTCCLKCmd(ENABLE);
+   
+  /* LCD Clock Source Selection */
+  RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+}
+
+static void setup_dac1(void)
+{
+  /* see 10.2 notes */
+
+  static GPIO_InitTypeDef GPIO_InitStructure;
+  static DAC_InitTypeDef DAC_InitStructure;
+
+  /* DAC clock path:
+     HSI (16mhz) -> SYSCLK -> HCLK(/1) -> PCLK1(/1)
+   */
+
+  /* set the AHB clock (HCLK) prescaler to 1 */
+  RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+  /* set the low speed APB clock (APB1, ie. PCLK1) prescaler to 1 */
+  RCC_PCLK1Config(RCC_HCLK_Div1);
+
+  /* enable DAC APB1 clock */
+  /* signal connections: HSI(16mhz) -> SYSCLK -> AHB */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
+
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; /* GPIO_Pin_5 for channel 2 */
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+  DAC_StructInit(&DAC_InitStructure);
+  DAC_InitStructure.DAC_Trigger = DAC_Trigger_None;
+#if 0 /* triangle waveform generation */
+  DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_Triangle;
+  DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_TriangleAmplitude_1;
+#else
+  DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
+  DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
+#endif
+  DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+  DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+  /* enable dac channel */
+  DAC_Cmd(DAC_Channel_1, ENABLE);
+}
+
+static inline void set_dac1_mv(unsigned int mv)
+{
+  /* mv the millivolts */
+
+  /* vref in millivolts */
+  /* #define CONFIG_VREF 5000 */
+#define CONFIG_VREF 3000
+
+  /* resolution in bits */
+#define CONFIG_DAC_RES 12
+
+  const uint16_t n = (mv * (1 << (CONFIG_DAC_RES - 1))) / CONFIG_VREF;
+  DAC_SetChannel1Data(DAC_Align_12b_R, n);
+}
+
+void main(void)
+{
+  static RCC_ClocksTypeDef RCC_Clocks;
+  static GPIO_InitTypeDef GPIO_InitStructure;
+  static uint16_t dac_value;
+  static unsigned int led_state = 0;
+
+  /* Configure Clocks for Application need */
+  RCC_Configuration();
+  
+  /* Configure RTC Clocks */
+  RTC_Configuration();
+
+#if 0
+  /* Set internal voltage regulator to 1.8v */
+  PWR_VoltageScalingConfig(PWR_VoltageScaling_Range1);
+  /* Wait Until the Voltage Regulator is ready */
+  while (PWR_GetFlagStatus(PWR_FLAG_VOS) != RESET) ;
+#endif
+
+  /* configure gpios */
+
+  /* Enable GPIOs clock */     
+  RCC_AHBPeriphClockCmd(LD_GPIO_PORT_CLK, ENABLE);
+
+  /* Configure the GPIO_LED pins  LD3 & LD4*/
+  GPIO_InitStructure.GPIO_Pin = LD_GREEN_GPIO_PIN | LD_BLUE_GPIO_PIN;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_Init(LD_GPIO_PORT, &GPIO_InitStructure);
+  GPIO_LOW(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);   
+  GPIO_LOW(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
+
+  setup_dac1();
+
+  dac_value = 0;
+
+  while (1)
+  {
+    DAC_SetChannel1Data(DAC_Align_12b_R, dac_value & 0xfff);
+    dac_value += 0x10;
+
+    if (led_state & 1) switch_leds_on();
+    else switch_leds_off();
+    led_state ^= 1;
+
+    delay();
+  }
+}
diff --git a/example/32l_dac/startup_stm32l1xx_md.s b/example/32l_dac/startup_stm32l1xx_md.s
new file mode 100644 (file)
index 0000000..9a8389c
--- /dev/null
@@ -0,0 +1,365 @@
+/**\r
+ ******************************************************************************\r
+ * @file      startup_stm32l1xx_md.s\r
+ * @author    MCD Application Team\r
+ * @version   V1.0.0\r
+ * @date      31-December-2010\r
+ * @brief     STM32L1xx Ultra Low Power Medium-density Devices vector table for \r
+ *            RIDE7 toolchain.\r
+ *            This module performs:\r
+ *                - Set the initial SP\r
+ *                - Set the initial PC == Reset_Handler,\r
+ *                - Set the vector table entries with the exceptions ISR address\r
+ *                - Branches to main in the C library (which eventually\r
+ *                  calls main()).\r
+ *            After Reset the Cortex-M3 processor is in Thread mode,\r
+ *            priority is Privileged, and the Stack is set to Main.\r
+ *******************************************************************************\r
+ * @attention\r
+ *\r
+ * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
+ * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
+ * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
+ * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
+ * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
+ * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
+ *\r
+ * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>\r
+ ******************************************************************************* \r
+ */\r
+    \r
+  .syntax unified\r
+  .cpu cortex-m3\r
+  .fpu softvfp\r
+  .thumb\r
+\r
+.global g_pfnVectors\r
+.global Default_Handler\r
+\r
+/* start address for the initialization values of the .data section. \r
+defined in linker script */\r
+.word _sidata\r
+/* start address for the .data section. defined in linker script */  \r
+.word _sdata\r
+/* end address for the .data section. defined in linker script */\r
+.word _edata\r
+/* start address for the .bss section. defined in linker script */\r
+.word _sbss\r
+/* end address for the .bss section. defined in linker script */\r
+.word _ebss\r
+\r
+.equ  BootRAM, 0xF108F85F\r
+/**\r
+ * @brief  This is the code that gets called when the processor first\r
+ *          starts execution following a reset event. Only the absolutely\r
+ *          necessary set is performed, after which the application\r
+ *          supplied main() routine is called. \r
+ * @param  None\r
+ * @retval : None\r
+*/\r
+\r
+    .section .text.Reset_Handler\r
+  .weak Reset_Handler\r
+  .type Reset_Handler, %function\r
+Reset_Handler:\r
+/* Copy the data segment initializers from flash to SRAM */  \r
+  movs r1, #0\r
+  b LoopCopyDataInit\r
+\r
+CopyDataInit:\r
+  ldr r3, =_sidata\r
+  ldr r3, [r3, r1]\r
+  str r3, [r0, r1]\r
+  adds r1, r1, #4\r
+    \r
+LoopCopyDataInit:\r
+  ldr r0, =_sdata\r
+  ldr r3, =_edata\r
+  adds r2, r0, r1\r
+  cmp r2, r3\r
+  bcc CopyDataInit\r
+  ldr r2, =_sbss\r
+  b LoopFillZerobss\r
+/* Zero fill the bss segment. */  \r
+FillZerobss:\r
+  movs r3, #0\r
+  str r3, [r2], #4\r
+    \r
+LoopFillZerobss:\r
+  ldr r3, = _ebss\r
+  cmp r2, r3\r
+  bcc FillZerobss\r
+/* Call the clock system intitialization function.*/\r
+/* let main do the system initialization */\r
+  bl  SystemInit\r
+/* Call the application's entry point.*/\r
+  bl main\r
+  bx lr\r
+.size Reset_Handler, .-Reset_Handler\r
+\r
+/**\r
+ * @brief  This is the code that gets called when the processor receives an \r
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving\r
+ *         the system state for examination by a debugger.\r
+ *\r
+ * @param  None     \r
+ * @retval None       \r
+*/\r
+    .section .text.Default_Handler,"ax",%progbits\r
+Default_Handler:\r
+Infinite_Loop:\r
+  b Infinite_Loop\r
+  .size Default_Handler, .-Default_Handler\r
+/*******************************************************************************\r
+*\r
+* The minimal vector table for a Cortex M3. Note that the proper constructs\r
+* must be placed on this to ensure that it ends up at physical address\r
+* 0x0000.0000.\r
+*******************************************************************************/    \r
+  .section .isr_vector,"a",%progbits\r
+  .type g_pfnVectors, %object\r
+  .size g_pfnVectors, .-g_pfnVectors\r
+    \r
+    \r
+g_pfnVectors:\r
+  .word _estack\r
+  .word Reset_Handler\r
+  .word NMI_Handler\r
+  .word HardFault_Handler\r
+  .word MemManage_Handler\r
+  .word BusFault_Handler\r
+  .word UsageFault_Handler\r
+  .word 0\r
+  .word 0\r
+  .word 0\r
+  .word 0\r
+  .word SVC_Handler\r
+  .word DebugMon_Handler\r
+  .word 0\r
+  .word PendSV_Handler\r
+  .word SysTick_Handler\r
+  .word WWDG_IRQHandler\r
+  .word PVD_IRQHandler\r
+  .word TAMPER_STAMP_IRQHandler\r
+  .word RTC_WKUP_IRQHandler\r
+  .word FLASH_IRQHandler\r
+  .word RCC_IRQHandler\r
+  .word EXTI0_IRQHandler\r
+  .word EXTI1_IRQHandler\r
+  .word EXTI2_IRQHandler\r
+  .word EXTI3_IRQHandler\r
+  .word EXTI4_IRQHandler\r
+  .word DMA1_Channel1_IRQHandler\r
+  .word DMA1_Channel2_IRQHandler\r
+  .word DMA1_Channel3_IRQHandler\r
+  .word DMA1_Channel4_IRQHandler\r
+  .word DMA1_Channel5_IRQHandler\r
+  .word DMA1_Channel6_IRQHandler\r
+  .word DMA1_Channel7_IRQHandler\r
+  .word ADC1_IRQHandler\r
+  .word USB_HP_IRQHandler\r
+  .word USB_LP_IRQHandler\r
+  .word DAC_IRQHandler\r
+  .word COMP_IRQHandler\r
+  .word EXTI9_5_IRQHandler\r
+  .word LCD_IRQHandler\r
+  .word TIM9_IRQHandler\r
+  .word TIM10_IRQHandler\r
+  .word TIM11_IRQHandler\r
+  .word TIM2_IRQHandler\r
+  .word TIM3_IRQHandler\r
+  .word TIM4_IRQHandler\r
+  .word I2C1_EV_IRQHandler\r
+  .word I2C1_ER_IRQHandler\r
+  .word I2C2_EV_IRQHandler\r
+  .word I2C2_ER_IRQHandler\r
+  .word SPI1_IRQHandler\r
+  .word SPI2_IRQHandler\r
+  .word USART1_IRQHandler\r
+  .word USART2_IRQHandler\r
+  .word USART3_IRQHandler\r
+  .word EXTI15_10_IRQHandler\r
+  .word RTC_Alarm_IRQHandler\r
+  .word USB_FS_WKUP_IRQHandler\r
+  .word TIM6_IRQHandler\r
+  .word TIM7_IRQHandler\r
+  .word 0\r
+  .word 0\r
+  .word 0\r
+  .word 0\r
+  .word 0\r
+  .word BootRAM          /* @0x108. This is for boot in RAM mode for \r
+                            STM32L15x ULtra Low Power Medium-density devices. */\r
+   \r
+/*******************************************************************************\r
+*\r
+* Provide weak aliases for each Exception handler to the Default_Handler. \r
+* As they are weak aliases, any function with the same name will override \r
+* this definition.\r
+*\r
+*******************************************************************************/\r
+    \r
+  .weak NMI_Handler\r
+  .thumb_set NMI_Handler,Default_Handler\r
+\r
+  .weak HardFault_Handler\r
+  .thumb_set HardFault_Handler,Default_Handler\r
+\r
+  .weak MemManage_Handler\r
+  .thumb_set MemManage_Handler,Default_Handler\r
+\r
+  .weak BusFault_Handler\r
+  .thumb_set BusFault_Handler,Default_Handler\r
+\r
+  .weak UsageFault_Handler\r
+  .thumb_set UsageFault_Handler,Default_Handler\r
+\r
+  .weak SVC_Handler\r
+  .thumb_set SVC_Handler,Default_Handler\r
+\r
+  .weak DebugMon_Handler\r
+  .thumb_set DebugMon_Handler,Default_Handler\r
+\r
+  .weak PendSV_Handler\r
+  .thumb_set PendSV_Handler,Default_Handler\r
+\r
+  .weak SysTick_Handler\r
+  .thumb_set SysTick_Handler,Default_Handler\r
+\r
+  .weak WWDG_IRQHandler\r
+  .thumb_set WWDG_IRQHandler,Default_Handler\r
+\r
+  .weak PVD_IRQHandler\r
+  .thumb_set PVD_IRQHandler,Default_Handler\r
+\r
+  .weak TAMPER_STAMP_IRQHandler\r
+  .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler\r
+\r
+  .weak RTC_WKUP_IRQHandler\r
+  .thumb_set RTC_WKUP_IRQHandler,Default_Handler\r
+\r
+  .weak FLASH_IRQHandler\r
+  .thumb_set FLASH_IRQHandler,Default_Handler\r
+\r
+  .weak RCC_IRQHandler\r
+  .thumb_set RCC_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI0_IRQHandler\r
+  .thumb_set EXTI0_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI1_IRQHandler\r
+  .thumb_set EXTI1_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI2_IRQHandler\r
+  .thumb_set EXTI2_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI3_IRQHandler\r
+  .thumb_set EXTI3_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI4_IRQHandler\r
+  .thumb_set EXTI4_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel1_IRQHandler\r
+  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel2_IRQHandler\r
+  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel3_IRQHandler\r
+  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel4_IRQHandler\r
+  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel5_IRQHandler\r
+  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel6_IRQHandler\r
+  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler\r
+\r
+  .weak DMA1_Channel7_IRQHandler\r
+  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler\r
+\r
+  .weak ADC1_IRQHandler\r
+  .thumb_set ADC1_IRQHandler,Default_Handler\r
+\r
+  .weak USB_HP_IRQHandler\r
+  .thumb_set USB_HP_IRQHandler,Default_Handler\r
+\r
+  .weak USB_LP_IRQHandler\r
+  .thumb_set USB_LP_IRQHandler,Default_Handler\r
+\r
+  .weak DAC_IRQHandler\r
+  .thumb_set DAC_IRQHandler,Default_Handler\r
+\r
+  .weak COMP_IRQHandler\r
+  .thumb_set COMP_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI9_5_IRQHandler\r
+  .thumb_set EXTI9_5_IRQHandler,Default_Handler\r
+\r
+  .weak LCD_IRQHandler\r
+  .thumb_set LCD_IRQHandler,Default_Handler\r
+  \r
+  .weak TIM9_IRQHandler\r
+  .thumb_set TIM9_IRQHandler,Default_Handler\r
+\r
+  .weak TIM10_IRQHandler\r
+  .thumb_set TIM10_IRQHandler,Default_Handler\r
+\r
+  .weak TIM11_IRQHandler\r
+  .thumb_set TIM11_IRQHandler,Default_Handler\r
+\r
+  .weak TIM2_IRQHandler\r
+  .thumb_set TIM2_IRQHandler,Default_Handler\r
+\r
+  .weak TIM3_IRQHandler\r
+  .thumb_set TIM3_IRQHandler,Default_Handler\r
+\r
+  .weak TIM4_IRQHandler\r
+  .thumb_set TIM4_IRQHandler,Default_Handler\r
+\r
+  .weak I2C1_EV_IRQHandler\r
+  .thumb_set I2C1_EV_IRQHandler,Default_Handler\r
+\r
+  .weak I2C1_ER_IRQHandler\r
+  .thumb_set I2C1_ER_IRQHandler,Default_Handler\r
+\r
+  .weak I2C2_EV_IRQHandler\r
+  .thumb_set I2C2_EV_IRQHandler,Default_Handler\r
+\r
+  .weak I2C2_ER_IRQHandler\r
+  .thumb_set I2C2_ER_IRQHandler,Default_Handler\r
+\r
+  .weak SPI1_IRQHandler\r
+  .thumb_set SPI1_IRQHandler,Default_Handler\r
+\r
+  .weak SPI2_IRQHandler\r
+  .thumb_set SPI2_IRQHandler,Default_Handler\r
+\r
+  .weak USART1_IRQHandler\r
+  .thumb_set USART1_IRQHandler,Default_Handler\r
+\r
+  .weak USART2_IRQHandler\r
+  .thumb_set USART2_IRQHandler,Default_Handler\r
+\r
+  .weak USART3_IRQHandler\r
+  .thumb_set USART3_IRQHandler,Default_Handler\r
+\r
+  .weak EXTI15_10_IRQHandler\r
+  .thumb_set EXTI15_10_IRQHandler,Default_Handler\r
+\r
+  .weak RTC_Alarm_IRQHandler\r
+  .thumb_set RTC_Alarm_IRQHandler,Default_Handler\r
+\r
+  .weak USB_FS_WKUP_IRQHandler\r
+  .thumb_set USB_FS_WKUP_IRQHandler,Default_Handler\r
+\r
+  .weak TIM6_IRQHandler\r
+  .thumb_set TIM6_IRQHandler,Default_Handler\r
+\r
+  .weak TIM7_IRQHandler\r
+  .thumb_set TIM7_IRQHandler,Default_Handler\r
+\r
+/******************** (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE***/\r
+\r
diff --git a/example/32l_dac/stm32_flash.ld b/example/32l_dac/stm32_flash.ld
new file mode 100644 (file)
index 0000000..146b16e
--- /dev/null
@@ -0,0 +1,173 @@
+/*
+*****************************************************************************
+**
+**  File        : stm32_flash.ld
+**
+**  Abstract    : Linker script for STM32L152RB Device with
+**                128KByte FLASH, 16KByte RAM
+**
+**                Set heap size, stack size and stack location according
+**                to application requirements.
+**
+**                Set memory bank area and size if external memory is used.
+**
+**  Target      : STMicroelectronics STM32
+**
+**  Environment : Atollic TrueSTUDIO(R)
+**
+**  Distribution: The file is distributed \93as is,\94 without any warranty
+**                of any kind.
+**
+**  (c)Copyright Atollic AB.
+**  You may use this file as-is or modify it according to the needs of your
+**  project. Distribution of this file (unmodified or modified) is not
+**  permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
+**  rights to distribute the assembled, compiled & linked contents of this
+**  file as part of an application binary file, provided that it is built
+**  using the Atollic TrueSTUDIO(R) toolchain.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20004000;    /* end of 16K 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 = 0x80; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+  FLASH (rx)      : ORIGIN = 0x08000000, LENGTH = 128K
+  RAM (xrw)       : ORIGIN = 0x20000000, LENGTH = 16K
+  MEMORY_B1 (rx)  : ORIGIN = 0x60000000, LENGTH = 0K
+  RW_EEPROM (rw)   : ORIGIN = 0x08080000, LENGTH = 32
+}
+
+/* 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 */
+       *(.eh_frame)
+
+    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
+
+  .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
+
+  /* User_heap_stack section, used to check that there is enough RAM left */
+  ._user_heap_stack :
+  {
+    . = ALIGN(4);
+    PROVIDE ( end = . );
+    PROVIDE ( _end = . );
+    . = . + _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 ( * )
+  }
+
+  .ARM.attributes 0 : { *(.ARM.attributes) }
+  
+  .DataFlash (NOLOAD): {*(.DataFlash)} >RW_EEPROM
+}
diff --git a/example/32l_dac/system_stm32l1xx.c b/example/32l_dac/system_stm32l1xx.c
new file mode 100644 (file)
index 0000000..6deab32
--- /dev/null
@@ -0,0 +1,367 @@
+/**\r
+  ******************************************************************************\r
+  * @file    system_stm32l1xx.c\r
+  * @author  MCD Application Team\r
+  * @version V1.0.0\r
+  * @date    2-June-2011\r
+  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.\r
+  *          This file contains the system clock configuration for STM32L1xx Ultra\r
+  *          Low Medium-density devices, and is generated by the clock configuration\r
+  *          tool "STM32L1xx_Clock_Configuration_V1.0.0.xls".\r
+  *             \r
+  * 1.  This file provides two functions and one global variable to be called from \r
+  *     user application:\r
+  *      - SystemInit(): Setups the system clock (System clock source, PLL Multiplier\r
+  *                      and Divider factors, AHB/APBx prescalers and Flash settings),\r
+  *                      depending on the configuration made in the clock xls tool. \r
+  *                      This function is called at startup just after reset and \r
+  *                      before branch to main program. This call is made inside\r
+  *                      the "startup_stm32l1xx_md.s" file.\r
+  *                        \r
+  *      - SystemCoreClock variable: Contains the core clock (HCLK), it can be used\r
+  *                                  by the user application to setup the SysTick \r
+  *                                  timer or configure other parameters.\r
+  *                                     \r
+  *      - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must\r
+  *                                 be called whenever the core clock is changed\r
+  *                                 during program execution.   \r
+  *      \r
+  * 2. After each device reset the MSI (2.1 MHz Range) is used as system clock source.\r
+  *    Then SystemInit() function is called, in "startup_stm32l1xx_md.s" file, to\r
+  *    configure the system clock before to branch to main program.    \r
+  *    \r
+  * 3. If the system clock source selected by user fails to startup, the SystemInit()\r
+  *    function will do nothing and MSI still used as system clock source. User can \r
+  *    add some code to deal with this issue inside the SetSysClock() function.       \r
+  * \r
+  * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define\r
+  *    in "stm32l1xx.h" file. When HSE is used as system clock source, directly or\r
+  *    through PLL, and you are using different crystal you have to adapt the HSE\r
+  *    value to your own configuration.\r
+  * \r
+  * 5. This file configures the system clock as follows:  \r
+  *=============================================================================\r
+  *                         System Clock Configuration\r
+  *=============================================================================\r
+  *        System clock source          | HSI\r
+  *----------------------------------------------------------------------------- \r
+  *        SYSCLK                       | 16000000 Hz\r
+  *----------------------------------------------------------------------------- \r
+  *        HCLK                         | 16000000 Hz\r
+  *----------------------------------------------------------------------------- \r
+  *        AHB Prescaler                | 1\r
+  *----------------------------------------------------------------------------- \r
+  *        APB1 Prescaler               | 1\r
+  *----------------------------------------------------------------------------- \r
+  *        APB2 Prescaler               | 1\r
+  *----------------------------------------------------------------------------- \r
+  *        HSE Frequency                | 8000000 Hz\r
+  *----------------------------------------------------------------------------- \r
+  *        PLL DIV                      | Not Used\r
+  *----------------------------------------------------------------------------- \r
+  *        PLL MUL                      | Not Used\r
+  *----------------------------------------------------------------------------- \r
+  *        VDD                          | 3.3 V\r
+  *----------------------------------------------------------------------------- \r
+  *        Vcore                        | 1.8 V (Range 1)\r
+  *----------------------------------------------------------------------------- \r
+  *        Flash Latency                | 0 WS\r
+  *----------------------------------------------------------------------------- \r
+  *        Require 48MHz for USB clock  | Disabled\r
+  *----------------------------------------------------------------------------- \r
+  *=============================================================================\r
+  ****************************************************************************** \r
+  * @attention\r
+  *\r
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
+  *\r
+  * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>\r
+  ******************************************************************************  \r
+  */\r
+\r
+/** @addtogroup CMSIS\r
+  * @{\r
+  */\r
+\r
+/** @addtogroup stm32l1xx_system\r
+  * @{\r
+  */  \r
+  \r
+/** @addtogroup STM32L1xx_System_Private_Includes\r
+  * @{\r
+  */\r
+\r
+#include "stm32l1xx.h"\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_TypesDefinitions\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_Defines\r
+  * @{\r
+  */\r
+/*!< Uncomment the following line if you need to relocate your vector Table in\r
+     Internal SRAM. */ \r
+/* #define VECT_TAB_SRAM */\r
+#define VECT_TAB_OFFSET  0x0 /*!< Vector Table base offset field. \r
+                                  This value must be a multiple of 0x200. */\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_Macros\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_Variables\r
+  * @{\r
+  */\r
+uint32_t SystemCoreClock    = 16000000;\r
+__I uint8_t PLLMulTable[9] = {3, 4, 6, 8, 12, 16, 24, 32, 48};\r
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes\r
+  * @{\r
+  */\r
+\r
+static void SetSysClock(void);\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @addtogroup STM32L1xx_System_Private_Functions\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @brief  Setup the microcontroller system.\r
+  *         Initialize the Embedded Flash Interface, the PLL and update the \r
+  *         SystemCoreClock variable.\r
+  * @param  None\r
+  * @retval None\r
+  */\r
+void SystemInit (void)\r
+{\r
+  /*!< Set MSION bit */\r
+  RCC->CR |= (uint32_t)0x00000100;\r
+\r
+  /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */\r
+  RCC->CFGR &= (uint32_t)0x88FFC00C;\r
+  \r
+  /*!< Reset HSION, HSEON, CSSON and PLLON bits */\r
+  RCC->CR &= (uint32_t)0xEEFEFFFE;\r
+\r
+  /*!< Reset HSEBYP bit */\r
+  RCC->CR &= (uint32_t)0xFFFBFFFF;\r
+\r
+  /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */\r
+  RCC->CFGR &= (uint32_t)0xFF02FFFF;\r
+\r
+  /*!< Disable all interrupts */\r
+  RCC->CIR = 0x00000000;\r
+    \r
+  /* Configure the System clock frequency, AHB/APBx prescalers and Flash settings */\r
+  SetSysClock();\r
+\r
+#ifdef VECT_TAB_SRAM\r
+  SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */\r
+#else\r
+  SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */\r
+#endif\r
+}\r
+\r
+/**\r
+  * @brief  Update SystemCoreClock according to Clock Register Values\r
+  * @note   - The system frequency computed by this function is not the real \r
+  *           frequency in the chip. It is calculated based on the predefined \r
+  *           constant and the selected clock source:\r
+  *             \r
+  *           - If SYSCLK source is MSI, SystemCoreClock will contain the MSI \r
+  *             value as defined by the MSI range.\r
+  *                                   \r
+  *           - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)\r
+  *                                              \r
+  *           - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)\r
+  *                          \r
+  *           - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) \r
+  *             or HSI_VALUE(*) multiplied/divided by the PLL factors.\r
+  *         \r
+  *         (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value\r
+  *             16 MHz) but the real value may vary depending on the variations\r
+  *             in voltage and temperature.   \r
+  *    \r
+  *         (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value\r
+  *              8 MHz), user has to ensure that HSE_VALUE is same as the real\r
+  *              frequency of the crystal used. Otherwise, this function may\r
+  *              have wrong result.\r
+  *                \r
+  *         - The result of this function could be not correct when using fractional\r
+  *           value for HSE crystal.  \r
+  * @param  None\r
+  * @retval None\r
+  */\r
+void SystemCoreClockUpdate (void)\r
+{\r
+  uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0;\r
+\r
+  /* Get SYSCLK source -------------------------------------------------------*/\r
+  tmp = RCC->CFGR & RCC_CFGR_SWS;\r
+  \r
+  switch (tmp)\r
+  {\r
+    case 0x00:  /* MSI used as system clock */\r
+      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;\r
+      SystemCoreClock = (32768 * (1 << (msirange + 1)));\r
+      break;\r
+    case 0x04:  /* HSI used as system clock */\r
+      SystemCoreClock = HSI_VALUE;\r
+      break;\r
+    case 0x08:  /* HSE used as system clock */\r
+      SystemCoreClock = HSE_VALUE;\r
+      break;\r
+    case 0x0C:  /* PLL used as system clock */\r
+      /* Get PLL clock source and multiplication factor ----------------------*/\r
+      pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;\r
+      plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;\r
+      pllmul = PLLMulTable[(pllmul >> 18)];\r
+      plldiv = (plldiv >> 22) + 1;\r
+      \r
+      pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;\r
+\r
+      if (pllsource == 0x00)\r
+      {\r
+        /* HSI oscillator clock selected as PLL clock entry */\r
+        SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);\r
+      }\r
+      else\r
+      {\r
+        /* HSE selected as PLL clock entry */\r
+        SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);\r
+      }\r
+      break;\r
+    default: /* MSI used as system clock */\r
+      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;\r
+      SystemCoreClock = (32768 * (1 << (msirange + 1)));\r
+      break;\r
+  }\r
+  /* Compute HCLK clock frequency --------------------------------------------*/\r
+  /* Get HCLK prescaler */\r
+  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];\r
+  /* HCLK clock frequency */\r
+  SystemCoreClock >>= tmp;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the System clock frequency, AHB/APBx prescalers and Flash \r
+  *         settings.\r
+  * @note   This function should be called only once the RCC clock configuration  \r
+  *         is reset to the default reset state (done in SystemInit() function).             \r
+  * @param  None\r
+  * @retval None\r
+  */\r
+static void SetSysClock(void)\r
+{\r
+  __IO uint32_t StartUpCounter = 0, HSIStatus = 0;\r
+  \r
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/\r
+  /* Enable HSI */\r
+  RCC->CR |= ((uint32_t)RCC_CR_HSION);\r
\r
+  /* Wait till HSI is ready and if Time out is reached exit */\r
+  do\r
+  {\r
+    HSIStatus = RCC->CR & RCC_CR_HSIRDY;\r
+  } while((HSIStatus == 0) && (StartUpCounter != HSI_STARTUP_TIMEOUT));\r
+\r
+  if ((RCC->CR & RCC_CR_HSIRDY) != RESET)\r
+  {\r
+    HSIStatus = (uint32_t)0x01;\r
+  }\r
+  else\r
+  {\r
+    HSIStatus = (uint32_t)0x00;\r
+  }\r
+    \r
+  if (HSIStatus == (uint32_t)0x01)\r
+  {\r
+    /* Flash 0 wait state */\r
+    FLASH->ACR &= ~FLASH_ACR_LATENCY;\r
+    \r
+    /* Disable Prefetch Buffer */\r
+    FLASH->ACR &= ~FLASH_ACR_PRFTEN;\r
+\r
+    /* Disable 64-bit access */\r
+    FLASH->ACR &= ~FLASH_ACR_ACC64;\r
+    \r
+\r
+    /* Power enable */\r
+    RCC->APB1ENR |= RCC_APB1ENR_PWREN;\r
+  \r
+    /* Select the Voltage Range 1 (1.8 V) */\r
+    PWR->CR = PWR_CR_VOS_0;\r
+  \r
+  \r
+    /* Wait Until the Voltage Regulator is ready */\r
+    while((PWR->CSR & PWR_CSR_VOSF) != RESET)\r
+    {\r
+    }\r
+      \r
+    /* HCLK = SYSCLK /1*/\r
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;\r
+    /* PCLK2 = HCLK /1*/\r
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;\r
+    \r
+    /* PCLK1 = HCLK /1*/\r
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;\r
+    \r
+    /* Select HSI as system clock source */\r
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));\r
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSI;\r
+\r
+    /* Wait till HSI is used as system clock source */\r
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_HSI)\r
+    {\r
+    }\r
+  }\r
+  else\r
+  {\r
+    /* If HSI fails to start-up, the application will have wrong clock\r
+       configuration. User can add here some code to deal with this error */\r
+  }\r
+}\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/\r
diff --git a/example/dac/Makefile b/example/dac/Makefile
deleted file mode 100644 (file)
index 84db69e..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-EXECUTABLE=dac.elf
-BIN_IMAGE=dac.bin
-
-CC=arm-none-eabi-gcc
-OBJCOPY=arm-none-eabi-objcopy
-
-CFLAGS=-O3 -mlittle-endian -mthumb
-ifeq ($(CONFIG_STM32L_DISCOVERY), 1)
-       CFLAGS+=-mcpu=cortex-m3 -DCONFIG_STM32L_DISCOVERY=1
-else ifeq ($(CONFIG_STM32VL_DISCOVERY), 1)
-       CFLAGS+=-mcpu=cortex-m3 -DCONFIG_STM32VL_DISCOVERY=1
-else ifeq ($(CONFIG_STM32F4_DISCOVERY), 1)
-       CFLAGS+=-mcpu=cortex-m4 -DCONFIG_STM32F4_DISCOVERY=1    
-else
-$(error "must specify CONFIG_ for board!")
-endif
-CFLAGS+=-ffreestanding -nostdlib -nostdinc
-
-# to run from FLASH
-CFLAGS+=-Wl,-T,stm32_flash.ld
-
-# stm32l_discovery lib
-CFLAGS+=-I../libstm32l_discovery/inc
-CFLAGS+=-I../libstm32l_discovery/inc/base
-CFLAGS+=-I../libstm32l_discovery/inc/core_support
-CFLAGS+=-I../libstm32l_discovery/inc/device_support
-
-all: $(BIN_IMAGE)
-
-$(BIN_IMAGE): $(EXECUTABLE)
-       $(OBJCOPY) -O binary $^ $@
-
-$(EXECUTABLE): main.c system_stm32l1xx.c startup_stm32l1xx_md.s
-       $(CC) $(CFLAGS) $^ -o $@  -L../libstm32l_discovery/build -lstm32l_discovery
-
-clean:
-       rm -rf $(EXECUTABLE)
-       rm -rf $(BIN_IMAGE)
-
-write: all
-       sudo ../../flash/flash write ./dac.bin 0x08000000
-
-.PHONY: all clean write
diff --git a/example/dac/discover_board.h b/example/dac/discover_board.h
deleted file mode 100644 (file)
index d93a184..0000000
+++ /dev/null
@@ -1,61 +0,0 @@
- /**\r
-  ******************************************************************************\r
-  * @file    discover_board.h\r
-  * @author  Microcontroller Division\r
-  * @version V1.0.2\r
-  * @date    September-2011\r
-  * @brief   Input/Output defines\r
-  ******************************************************************************\r
-  * @copy\r
-  *\r
-  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
-  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
-  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
-  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
-  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
-  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
-  *\r
-  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>\r
-  */\r
-\r
-/* Define to prevent recursive inclusion -------------------------------------*/\r
-\r
-#ifndef __DISCOVER_BOARD_H\r
-#define __DISCOVER_BOARD_H\r
-\r
-/* Includes ------------------------------------------------------------------*/\r
-/* #include "stm32l1xx.h"   */\r
-\r
-#define bool _Bool\r
-#define FALSE 0\r
-#define TRUE !FALSE\r
-\r
-/* MACROs for SET, RESET or TOGGLE Output port */\r
-\r
-#define GPIO_HIGH(a,b)                 a->BSRRL = b\r
-#define GPIO_LOW(a,b)          a->BSRRH = b\r
-#define GPIO_TOGGLE(a,b)       a->ODR ^= b \r
-\r
-#define USERBUTTON_GPIO_PORT   GPIOA\r
-#define USERBUTTON_GPIO_PIN     GPIO_Pin_0\r
-#define USERBUTTON_GPIO_CLK     RCC_AHBPeriph_GPIOA\r
-\r
-#define LD_GPIO_PORT           GPIOB\r
-#define LD_GREEN_GPIO_PIN              GPIO_Pin_7\r
-#define LD_BLUE_GPIO_PIN             GPIO_Pin_6\r
-#define LD_GPIO_PORT_CLK             RCC_AHBPeriph_GPIOB\r
-\r
-#define CTN_GPIO_PORT           GPIOC\r
-#define CTN_CNTEN_GPIO_PIN      GPIO_Pin_13\r
-#define CTN_GPIO_CLK            RCC_AHBPeriph_GPIOC\r
-\r
-#define WAKEUP_GPIO_PORT        GPIOA\r
-\r
-#define IDD_MEASURE_PORT       GPIOA\r
-#define IDD_MEASURE             GPIO_Pin_4\r
-\r
-\r
-#endif\r
-\r
-\r
-/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/\r
diff --git a/example/dac/main.c b/example/dac/main.c
deleted file mode 100644 (file)
index 1f89d33..0000000
+++ /dev/null
@@ -1,242 +0,0 @@
-/* base headers */
-#include "stdint.h"
-
-/* libstm32l_discovery headers */
-#include "stm32l1xx_gpio.h"
-#include "stm32l1xx_adc.h"
-#include "stm32l1xx_dac.h"
-#include "stm32l1xx_lcd.h"
-#include "stm32l1xx_rcc.h"
-#include "stm32l1xx_rtc.h"
-#include "stm32l1xx_exti.h"
-#include "stm32l1xx_pwr.h"
-#include "stm32l1xx_flash.h"
-#include "stm32l1xx_syscfg.h"
-#include "stm32l1xx_dbgmcu.h"
-
-/* board specific macros */
-#include "discover_board.h"
-
-
-/* hardware configuration */
-
-#if CONFIG_STM32VL_DISCOVERY
-
-# define GPIOC 0x40011000 /* port C */
-# define GPIOC_CRH (GPIOC + 0x04) /* port configuration register high */
-# define GPIOC_ODR (GPIOC + 0x0c) /* port output data register */
-
-# define LED_BLUE (1 << 8) /* port C, pin 8 */
-# define LED_GREEN (1 << 9) /* port C, pin 9 */
-
-static inline void setup_leds(void)
-{
-  *(volatile uint32_t*)GPIOC_CRH = 0x44444411;
-}
-
-static inline void switch_leds_on(void)
-{
-  *(volatile uint32_t*)GPIOC_ODR = LED_BLUE | LED_GREEN;
-}
-
-static inline void switch_leds_off(void)
-{
-  *(volatile uint32_t*)GPIOC_ODR = 0;
-}
-
-#elif CONFIG_STM32L_DISCOVERY
-
-# define GPIOB_MODER (GPIOB + 0x00) /* port mode register */
-# define GPIOB_ODR (GPIOB + 0x14) /* port output data register */
-
-# define LED_BLUE (1 << 6) /* port B, pin 6 */
-# define LED_GREEN (1 << 7) /* port B, pin 7 */
-
-static inline void setup_leds(void)
-{
-  /* configure port 6 and 7 as output */
-  *(volatile uint32_t*)GPIOB_MODER |= (1 << (7 * 2)) | (1 << (6 * 2));
-}
-
-static inline void switch_leds_on(void)
-{
-  GPIO_HIGH(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);  
-  GPIO_HIGH(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
-}
-
-static inline void switch_leds_off(void)
-{
-  GPIO_LOW(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);   
-  GPIO_LOW(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
-}
-
-#endif /* otherwise, error */
-
-
-#define delay()                                                \
-do {                                                   \
-  volatile unsigned int i;                             \
-  for (i = 0; i < 1000000; ++i)                                \
-    __asm__ __volatile__ ("nop\n\t":::"memory");       \
-} while (0)
-
-
-static void RCC_Configuration(void)
-{
-  /* HSI is 16mhz RC clock directly fed to SYSCLK (rm00038, figure 9) */
-
-  /* enable the HSI clock (high speed internal) */
-  RCC_HSICmd(ENABLE);
-  
-  /* wail til HSI ready */
-  while (RCC_GetFlagStatus(RCC_FLAG_HSIRDY) == RESET)
-  {}
-
-  /* at startup, SYSCLK driven by MSI. set to HSI */
-  RCC_SYSCLKConfig(RCC_SYSCLKSource_HSI);
-  
-  /* set MSI to 4mhz */
-  RCC_MSIRangeConfig(RCC_MSIRange_6);
-
-  /* turn HSE off */
-  RCC_HSEConfig(RCC_HSE_OFF);  
-  if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
-  {
-    while (1) ;
-  }
-}
-
-
-static void RTC_Configuration(void)
-{
-  /* Allow access to the RTC */
-  PWR_RTCAccessCmd(ENABLE);
-
-  /* Reset Backup Domain */
-  RCC_RTCResetCmd(ENABLE);
-  RCC_RTCResetCmd(DISABLE);
-
-  /* LSE Enable */
-  RCC_LSEConfig(RCC_LSE_ON);
-
-  /* Wait till LSE is ready */
-  while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
-  {}
-  
-  RCC_RTCCLKCmd(ENABLE);
-   
-  /* LCD Clock Source Selection */
-  RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
-
-}
-
-static void setup_dac1(void)
-{
-  /* see 10.2 notes */
-
-  static GPIO_InitTypeDef GPIO_InitStructure;
-  static DAC_InitTypeDef DAC_InitStructure;
-
-  /* DAC clock path:
-     HSI (16mhz) -> SYSCLK -> HCLK(/1) -> PCLK1(/1)
-   */
-
-  /* set the AHB clock (HCLK) prescaler to 1 */
-  RCC_HCLKConfig(RCC_SYSCLK_Div1);
-
-  /* set the low speed APB clock (APB1, ie. PCLK1) prescaler to 1 */
-  RCC_PCLK1Config(RCC_HCLK_Div1);
-
-  /* enable DAC APB1 clock */
-  /* signal connections: HSI(16mhz) -> SYSCLK -> AHB */
-  RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
-
-  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; /* GPIO_Pin_5 for channel 2 */
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
-  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
-  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
-  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
-  GPIO_Init(GPIOA, &GPIO_InitStructure);
-
-  DAC_StructInit(&DAC_InitStructure);
-  DAC_InitStructure.DAC_Trigger = DAC_Trigger_None;
-#if 0 /* triangle waveform generation */
-  DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_Triangle;
-  DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_TriangleAmplitude_1;
-#else
-  DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
-  DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
-#endif
-  DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
-  DAC_Init(DAC_Channel_1, &DAC_InitStructure);
-
-  /* enable dac channel */
-  DAC_Cmd(DAC_Channel_1, ENABLE);
-}
-
-static inline void set_dac1_mv(unsigned int mv)
-{
-  /* mv the millivolts */
-
-  /* vref in millivolts */
-  /* #define CONFIG_VREF 5000 */
-#define CONFIG_VREF 3000
-
-  /* resolution in bits */
-#define CONFIG_DAC_RES 12
-
-  const uint16_t n = (mv * (1 << (CONFIG_DAC_RES - 1))) / CONFIG_VREF;
-  DAC_SetChannel1Data(DAC_Align_12b_R, n);
-}
-
-void main(void)
-{
-  static RCC_ClocksTypeDef RCC_Clocks;
-  static GPIO_InitTypeDef GPIO_InitStructure;
-  static uint16_t dac_value;
-  static unsigned int led_state = 0;
-
-  /* Configure Clocks for Application need */
-  RCC_Configuration();
-  
-  /* Configure RTC Clocks */
-  RTC_Configuration();
-
-#if 0
-  /* Set internal voltage regulator to 1.8v */
-  PWR_VoltageScalingConfig(PWR_VoltageScaling_Range1);
-  /* Wait Until the Voltage Regulator is ready */
-  while (PWR_GetFlagStatus(PWR_FLAG_VOS) != RESET) ;
-#endif
-
-  /* configure gpios */
-
-  /* Enable GPIOs clock */     
-  RCC_AHBPeriphClockCmd(LD_GPIO_PORT_CLK, ENABLE);
-
-  /* Configure the GPIO_LED pins  LD3 & LD4*/
-  GPIO_InitStructure.GPIO_Pin = LD_GREEN_GPIO_PIN | LD_BLUE_GPIO_PIN;
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
-  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
-  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
-  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
-  GPIO_Init(LD_GPIO_PORT, &GPIO_InitStructure);
-  GPIO_LOW(LD_GPIO_PORT, LD_GREEN_GPIO_PIN);   
-  GPIO_LOW(LD_GPIO_PORT, LD_BLUE_GPIO_PIN);
-
-  setup_dac1();
-
-  dac_value = 0;
-
-  while (1)
-  {
-    DAC_SetChannel1Data(DAC_Align_12b_R, dac_value & 0xfff);
-    dac_value += 0x10;
-
-    if (led_state & 1) switch_leds_on();
-    else switch_leds_off();
-    led_state ^= 1;
-
-    delay();
-  }
-}
diff --git a/example/dac/startup_stm32l1xx_md.s b/example/dac/startup_stm32l1xx_md.s
deleted file mode 100644 (file)
index 9a8389c..0000000
+++ /dev/null
@@ -1,365 +0,0 @@
-/**\r
- ******************************************************************************\r
- * @file      startup_stm32l1xx_md.s\r
- * @author    MCD Application Team\r
- * @version   V1.0.0\r
- * @date      31-December-2010\r
- * @brief     STM32L1xx Ultra Low Power Medium-density Devices vector table for \r
- *            RIDE7 toolchain.\r
- *            This module performs:\r
- *                - Set the initial SP\r
- *                - Set the initial PC == Reset_Handler,\r
- *                - Set the vector table entries with the exceptions ISR address\r
- *                - Branches to main in the C library (which eventually\r
- *                  calls main()).\r
- *            After Reset the Cortex-M3 processor is in Thread mode,\r
- *            priority is Privileged, and the Stack is set to Main.\r
- *******************************************************************************\r
- * @attention\r
- *\r
- * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
- * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
- * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
- * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
- * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
- * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
- *\r
- * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>\r
- ******************************************************************************* \r
- */\r
-    \r
-  .syntax unified\r
-  .cpu cortex-m3\r
-  .fpu softvfp\r
-  .thumb\r
-\r
-.global g_pfnVectors\r
-.global Default_Handler\r
-\r
-/* start address for the initialization values of the .data section. \r
-defined in linker script */\r
-.word _sidata\r
-/* start address for the .data section. defined in linker script */  \r
-.word _sdata\r
-/* end address for the .data section. defined in linker script */\r
-.word _edata\r
-/* start address for the .bss section. defined in linker script */\r
-.word _sbss\r
-/* end address for the .bss section. defined in linker script */\r
-.word _ebss\r
-\r
-.equ  BootRAM, 0xF108F85F\r
-/**\r
- * @brief  This is the code that gets called when the processor first\r
- *          starts execution following a reset event. Only the absolutely\r
- *          necessary set is performed, after which the application\r
- *          supplied main() routine is called. \r
- * @param  None\r
- * @retval : None\r
-*/\r
-\r
-    .section .text.Reset_Handler\r
-  .weak Reset_Handler\r
-  .type Reset_Handler, %function\r
-Reset_Handler:\r
-/* Copy the data segment initializers from flash to SRAM */  \r
-  movs r1, #0\r
-  b LoopCopyDataInit\r
-\r
-CopyDataInit:\r
-  ldr r3, =_sidata\r
-  ldr r3, [r3, r1]\r
-  str r3, [r0, r1]\r
-  adds r1, r1, #4\r
-    \r
-LoopCopyDataInit:\r
-  ldr r0, =_sdata\r
-  ldr r3, =_edata\r
-  adds r2, r0, r1\r
-  cmp r2, r3\r
-  bcc CopyDataInit\r
-  ldr r2, =_sbss\r
-  b LoopFillZerobss\r
-/* Zero fill the bss segment. */  \r
-FillZerobss:\r
-  movs r3, #0\r
-  str r3, [r2], #4\r
-    \r
-LoopFillZerobss:\r
-  ldr r3, = _ebss\r
-  cmp r2, r3\r
-  bcc FillZerobss\r
-/* Call the clock system intitialization function.*/\r
-/* let main do the system initialization */\r
-  bl  SystemInit\r
-/* Call the application's entry point.*/\r
-  bl main\r
-  bx lr\r
-.size Reset_Handler, .-Reset_Handler\r
-\r
-/**\r
- * @brief  This is the code that gets called when the processor receives an \r
- *         unexpected interrupt.  This simply enters an infinite loop, preserving\r
- *         the system state for examination by a debugger.\r
- *\r
- * @param  None     \r
- * @retval None       \r
-*/\r
-    .section .text.Default_Handler,"ax",%progbits\r
-Default_Handler:\r
-Infinite_Loop:\r
-  b Infinite_Loop\r
-  .size Default_Handler, .-Default_Handler\r
-/*******************************************************************************\r
-*\r
-* The minimal vector table for a Cortex M3. Note that the proper constructs\r
-* must be placed on this to ensure that it ends up at physical address\r
-* 0x0000.0000.\r
-*******************************************************************************/    \r
-  .section .isr_vector,"a",%progbits\r
-  .type g_pfnVectors, %object\r
-  .size g_pfnVectors, .-g_pfnVectors\r
-    \r
-    \r
-g_pfnVectors:\r
-  .word _estack\r
-  .word Reset_Handler\r
-  .word NMI_Handler\r
-  .word HardFault_Handler\r
-  .word MemManage_Handler\r
-  .word BusFault_Handler\r
-  .word UsageFault_Handler\r
-  .word 0\r
-  .word 0\r
-  .word 0\r
-  .word 0\r
-  .word SVC_Handler\r
-  .word DebugMon_Handler\r
-  .word 0\r
-  .word PendSV_Handler\r
-  .word SysTick_Handler\r
-  .word WWDG_IRQHandler\r
-  .word PVD_IRQHandler\r
-  .word TAMPER_STAMP_IRQHandler\r
-  .word RTC_WKUP_IRQHandler\r
-  .word FLASH_IRQHandler\r
-  .word RCC_IRQHandler\r
-  .word EXTI0_IRQHandler\r
-  .word EXTI1_IRQHandler\r
-  .word EXTI2_IRQHandler\r
-  .word EXTI3_IRQHandler\r
-  .word EXTI4_IRQHandler\r
-  .word DMA1_Channel1_IRQHandler\r
-  .word DMA1_Channel2_IRQHandler\r
-  .word DMA1_Channel3_IRQHandler\r
-  .word DMA1_Channel4_IRQHandler\r
-  .word DMA1_Channel5_IRQHandler\r
-  .word DMA1_Channel6_IRQHandler\r
-  .word DMA1_Channel7_IRQHandler\r
-  .word ADC1_IRQHandler\r
-  .word USB_HP_IRQHandler\r
-  .word USB_LP_IRQHandler\r
-  .word DAC_IRQHandler\r
-  .word COMP_IRQHandler\r
-  .word EXTI9_5_IRQHandler\r
-  .word LCD_IRQHandler\r
-  .word TIM9_IRQHandler\r
-  .word TIM10_IRQHandler\r
-  .word TIM11_IRQHandler\r
-  .word TIM2_IRQHandler\r
-  .word TIM3_IRQHandler\r
-  .word TIM4_IRQHandler\r
-  .word I2C1_EV_IRQHandler\r
-  .word I2C1_ER_IRQHandler\r
-  .word I2C2_EV_IRQHandler\r
-  .word I2C2_ER_IRQHandler\r
-  .word SPI1_IRQHandler\r
-  .word SPI2_IRQHandler\r
-  .word USART1_IRQHandler\r
-  .word USART2_IRQHandler\r
-  .word USART3_IRQHandler\r
-  .word EXTI15_10_IRQHandler\r
-  .word RTC_Alarm_IRQHandler\r
-  .word USB_FS_WKUP_IRQHandler\r
-  .word TIM6_IRQHandler\r
-  .word TIM7_IRQHandler\r
-  .word 0\r
-  .word 0\r
-  .word 0\r
-  .word 0\r
-  .word 0\r
-  .word BootRAM          /* @0x108. This is for boot in RAM mode for \r
-                            STM32L15x ULtra Low Power Medium-density devices. */\r
-   \r
-/*******************************************************************************\r
-*\r
-* Provide weak aliases for each Exception handler to the Default_Handler. \r
-* As they are weak aliases, any function with the same name will override \r
-* this definition.\r
-*\r
-*******************************************************************************/\r
-    \r
-  .weak NMI_Handler\r
-  .thumb_set NMI_Handler,Default_Handler\r
-\r
-  .weak HardFault_Handler\r
-  .thumb_set HardFault_Handler,Default_Handler\r
-\r
-  .weak MemManage_Handler\r
-  .thumb_set MemManage_Handler,Default_Handler\r
-\r
-  .weak BusFault_Handler\r
-  .thumb_set BusFault_Handler,Default_Handler\r
-\r
-  .weak UsageFault_Handler\r
-  .thumb_set UsageFault_Handler,Default_Handler\r
-\r
-  .weak SVC_Handler\r
-  .thumb_set SVC_Handler,Default_Handler\r
-\r
-  .weak DebugMon_Handler\r
-  .thumb_set DebugMon_Handler,Default_Handler\r
-\r
-  .weak PendSV_Handler\r
-  .thumb_set PendSV_Handler,Default_Handler\r
-\r
-  .weak SysTick_Handler\r
-  .thumb_set SysTick_Handler,Default_Handler\r
-\r
-  .weak WWDG_IRQHandler\r
-  .thumb_set WWDG_IRQHandler,Default_Handler\r
-\r
-  .weak PVD_IRQHandler\r
-  .thumb_set PVD_IRQHandler,Default_Handler\r
-\r
-  .weak TAMPER_STAMP_IRQHandler\r
-  .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler\r
-\r
-  .weak RTC_WKUP_IRQHandler\r
-  .thumb_set RTC_WKUP_IRQHandler,Default_Handler\r
-\r
-  .weak FLASH_IRQHandler\r
-  .thumb_set FLASH_IRQHandler,Default_Handler\r
-\r
-  .weak RCC_IRQHandler\r
-  .thumb_set RCC_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI0_IRQHandler\r
-  .thumb_set EXTI0_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI1_IRQHandler\r
-  .thumb_set EXTI1_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI2_IRQHandler\r
-  .thumb_set EXTI2_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI3_IRQHandler\r
-  .thumb_set EXTI3_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI4_IRQHandler\r
-  .thumb_set EXTI4_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel1_IRQHandler\r
-  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel2_IRQHandler\r
-  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel3_IRQHandler\r
-  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel4_IRQHandler\r
-  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel5_IRQHandler\r
-  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel6_IRQHandler\r
-  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler\r
-\r
-  .weak DMA1_Channel7_IRQHandler\r
-  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler\r
-\r
-  .weak ADC1_IRQHandler\r
-  .thumb_set ADC1_IRQHandler,Default_Handler\r
-\r
-  .weak USB_HP_IRQHandler\r
-  .thumb_set USB_HP_IRQHandler,Default_Handler\r
-\r
-  .weak USB_LP_IRQHandler\r
-  .thumb_set USB_LP_IRQHandler,Default_Handler\r
-\r
-  .weak DAC_IRQHandler\r
-  .thumb_set DAC_IRQHandler,Default_Handler\r
-\r
-  .weak COMP_IRQHandler\r
-  .thumb_set COMP_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI9_5_IRQHandler\r
-  .thumb_set EXTI9_5_IRQHandler,Default_Handler\r
-\r
-  .weak LCD_IRQHandler\r
-  .thumb_set LCD_IRQHandler,Default_Handler\r
-  \r
-  .weak TIM9_IRQHandler\r
-  .thumb_set TIM9_IRQHandler,Default_Handler\r
-\r
-  .weak TIM10_IRQHandler\r
-  .thumb_set TIM10_IRQHandler,Default_Handler\r
-\r
-  .weak TIM11_IRQHandler\r
-  .thumb_set TIM11_IRQHandler,Default_Handler\r
-\r
-  .weak TIM2_IRQHandler\r
-  .thumb_set TIM2_IRQHandler,Default_Handler\r
-\r
-  .weak TIM3_IRQHandler\r
-  .thumb_set TIM3_IRQHandler,Default_Handler\r
-\r
-  .weak TIM4_IRQHandler\r
-  .thumb_set TIM4_IRQHandler,Default_Handler\r
-\r
-  .weak I2C1_EV_IRQHandler\r
-  .thumb_set I2C1_EV_IRQHandler,Default_Handler\r
-\r
-  .weak I2C1_ER_IRQHandler\r
-  .thumb_set I2C1_ER_IRQHandler,Default_Handler\r
-\r
-  .weak I2C2_EV_IRQHandler\r
-  .thumb_set I2C2_EV_IRQHandler,Default_Handler\r
-\r
-  .weak I2C2_ER_IRQHandler\r
-  .thumb_set I2C2_ER_IRQHandler,Default_Handler\r
-\r
-  .weak SPI1_IRQHandler\r
-  .thumb_set SPI1_IRQHandler,Default_Handler\r
-\r
-  .weak SPI2_IRQHandler\r
-  .thumb_set SPI2_IRQHandler,Default_Handler\r
-\r
-  .weak USART1_IRQHandler\r
-  .thumb_set USART1_IRQHandler,Default_Handler\r
-\r
-  .weak USART2_IRQHandler\r
-  .thumb_set USART2_IRQHandler,Default_Handler\r
-\r
-  .weak USART3_IRQHandler\r
-  .thumb_set USART3_IRQHandler,Default_Handler\r
-\r
-  .weak EXTI15_10_IRQHandler\r
-  .thumb_set EXTI15_10_IRQHandler,Default_Handler\r
-\r
-  .weak RTC_Alarm_IRQHandler\r
-  .thumb_set RTC_Alarm_IRQHandler,Default_Handler\r
-\r
-  .weak USB_FS_WKUP_IRQHandler\r
-  .thumb_set USB_FS_WKUP_IRQHandler,Default_Handler\r
-\r
-  .weak TIM6_IRQHandler\r
-  .thumb_set TIM6_IRQHandler,Default_Handler\r
-\r
-  .weak TIM7_IRQHandler\r
-  .thumb_set TIM7_IRQHandler,Default_Handler\r
-\r
-/******************** (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE***/\r
-\r
diff --git a/example/dac/stm32_flash.ld b/example/dac/stm32_flash.ld
deleted file mode 100644 (file)
index 146b16e..0000000
+++ /dev/null
@@ -1,173 +0,0 @@
-/*
-*****************************************************************************
-**
-**  File        : stm32_flash.ld
-**
-**  Abstract    : Linker script for STM32L152RB Device with
-**                128KByte FLASH, 16KByte RAM
-**
-**                Set heap size, stack size and stack location according
-**                to application requirements.
-**
-**                Set memory bank area and size if external memory is used.
-**
-**  Target      : STMicroelectronics STM32
-**
-**  Environment : Atollic TrueSTUDIO(R)
-**
-**  Distribution: The file is distributed \93as is,\94 without any warranty
-**                of any kind.
-**
-**  (c)Copyright Atollic AB.
-**  You may use this file as-is or modify it according to the needs of your
-**  project. Distribution of this file (unmodified or modified) is not
-**  permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
-**  rights to distribute the assembled, compiled & linked contents of this
-**  file as part of an application binary file, provided that it is built
-**  using the Atollic TrueSTUDIO(R) toolchain.
-**
-*****************************************************************************
-*/
-
-/* Entry Point */
-ENTRY(Reset_Handler)
-
-/* Highest address of the user mode stack */
-_estack = 0x20004000;    /* end of 16K 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 = 0x80; /* required amount of stack */
-
-/* Specify the memory areas */
-MEMORY
-{
-  FLASH (rx)      : ORIGIN = 0x08000000, LENGTH = 128K
-  RAM (xrw)       : ORIGIN = 0x20000000, LENGTH = 16K
-  MEMORY_B1 (rx)  : ORIGIN = 0x60000000, LENGTH = 0K
-  RW_EEPROM (rw)   : ORIGIN = 0x08080000, LENGTH = 32
-}
-
-/* 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 */
-       *(.eh_frame)
-
-    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
-
-  .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
-
-  /* User_heap_stack section, used to check that there is enough RAM left */
-  ._user_heap_stack :
-  {
-    . = ALIGN(4);
-    PROVIDE ( end = . );
-    PROVIDE ( _end = . );
-    . = . + _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 ( * )
-  }
-
-  .ARM.attributes 0 : { *(.ARM.attributes) }
-  
-  .DataFlash (NOLOAD): {*(.DataFlash)} >RW_EEPROM
-}
diff --git a/example/dac/system_stm32l1xx.c b/example/dac/system_stm32l1xx.c
deleted file mode 100644 (file)
index 6deab32..0000000
+++ /dev/null
@@ -1,367 +0,0 @@
-/**\r
-  ******************************************************************************\r
-  * @file    system_stm32l1xx.c\r
-  * @author  MCD Application Team\r
-  * @version V1.0.0\r
-  * @date    2-June-2011\r
-  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.\r
-  *          This file contains the system clock configuration for STM32L1xx Ultra\r
-  *          Low Medium-density devices, and is generated by the clock configuration\r
-  *          tool "STM32L1xx_Clock_Configuration_V1.0.0.xls".\r
-  *             \r
-  * 1.  This file provides two functions and one global variable to be called from \r
-  *     user application:\r
-  *      - SystemInit(): Setups the system clock (System clock source, PLL Multiplier\r
-  *                      and Divider factors, AHB/APBx prescalers and Flash settings),\r
-  *                      depending on the configuration made in the clock xls tool. \r
-  *                      This function is called at startup just after reset and \r
-  *                      before branch to main program. This call is made inside\r
-  *                      the "startup_stm32l1xx_md.s" file.\r
-  *                        \r
-  *      - SystemCoreClock variable: Contains the core clock (HCLK), it can be used\r
-  *                                  by the user application to setup the SysTick \r
-  *                                  timer or configure other parameters.\r
-  *                                     \r
-  *      - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must\r
-  *                                 be called whenever the core clock is changed\r
-  *                                 during program execution.   \r
-  *      \r
-  * 2. After each device reset the MSI (2.1 MHz Range) is used as system clock source.\r
-  *    Then SystemInit() function is called, in "startup_stm32l1xx_md.s" file, to\r
-  *    configure the system clock before to branch to main program.    \r
-  *    \r
-  * 3. If the system clock source selected by user fails to startup, the SystemInit()\r
-  *    function will do nothing and MSI still used as system clock source. User can \r
-  *    add some code to deal with this issue inside the SetSysClock() function.       \r
-  * \r
-  * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define\r
-  *    in "stm32l1xx.h" file. When HSE is used as system clock source, directly or\r
-  *    through PLL, and you are using different crystal you have to adapt the HSE\r
-  *    value to your own configuration.\r
-  * \r
-  * 5. This file configures the system clock as follows:  \r
-  *=============================================================================\r
-  *                         System Clock Configuration\r
-  *=============================================================================\r
-  *        System clock source          | HSI\r
-  *----------------------------------------------------------------------------- \r
-  *        SYSCLK                       | 16000000 Hz\r
-  *----------------------------------------------------------------------------- \r
-  *        HCLK                         | 16000000 Hz\r
-  *----------------------------------------------------------------------------- \r
-  *        AHB Prescaler                | 1\r
-  *----------------------------------------------------------------------------- \r
-  *        APB1 Prescaler               | 1\r
-  *----------------------------------------------------------------------------- \r
-  *        APB2 Prescaler               | 1\r
-  *----------------------------------------------------------------------------- \r
-  *        HSE Frequency                | 8000000 Hz\r
-  *----------------------------------------------------------------------------- \r
-  *        PLL DIV                      | Not Used\r
-  *----------------------------------------------------------------------------- \r
-  *        PLL MUL                      | Not Used\r
-  *----------------------------------------------------------------------------- \r
-  *        VDD                          | 3.3 V\r
-  *----------------------------------------------------------------------------- \r
-  *        Vcore                        | 1.8 V (Range 1)\r
-  *----------------------------------------------------------------------------- \r
-  *        Flash Latency                | 0 WS\r
-  *----------------------------------------------------------------------------- \r
-  *        Require 48MHz for USB clock  | Disabled\r
-  *----------------------------------------------------------------------------- \r
-  *=============================================================================\r
-  ****************************************************************************** \r
-  * @attention\r
-  *\r
-  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
-  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
-  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
-  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
-  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
-  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
-  *\r
-  * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>\r
-  ******************************************************************************  \r
-  */\r
-\r
-/** @addtogroup CMSIS\r
-  * @{\r
-  */\r
-\r
-/** @addtogroup stm32l1xx_system\r
-  * @{\r
-  */  \r
-  \r
-/** @addtogroup STM32L1xx_System_Private_Includes\r
-  * @{\r
-  */\r
-\r
-#include "stm32l1xx.h"\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_TypesDefinitions\r
-  * @{\r
-  */\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_Defines\r
-  * @{\r
-  */\r
-/*!< Uncomment the following line if you need to relocate your vector Table in\r
-     Internal SRAM. */ \r
-/* #define VECT_TAB_SRAM */\r
-#define VECT_TAB_OFFSET  0x0 /*!< Vector Table base offset field. \r
-                                  This value must be a multiple of 0x200. */\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_Macros\r
-  * @{\r
-  */\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_Variables\r
-  * @{\r
-  */\r
-uint32_t SystemCoreClock    = 16000000;\r
-__I uint8_t PLLMulTable[9] = {3, 4, 6, 8, 12, 16, 24, 32, 48};\r
-__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes\r
-  * @{\r
-  */\r
-\r
-static void SetSysClock(void);\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/** @addtogroup STM32L1xx_System_Private_Functions\r
-  * @{\r
-  */\r
-\r
-/**\r
-  * @brief  Setup the microcontroller system.\r
-  *         Initialize the Embedded Flash Interface, the PLL and update the \r
-  *         SystemCoreClock variable.\r
-  * @param  None\r
-  * @retval None\r
-  */\r
-void SystemInit (void)\r
-{\r
-  /*!< Set MSION bit */\r
-  RCC->CR |= (uint32_t)0x00000100;\r
-\r
-  /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */\r
-  RCC->CFGR &= (uint32_t)0x88FFC00C;\r
-  \r
-  /*!< Reset HSION, HSEON, CSSON and PLLON bits */\r
-  RCC->CR &= (uint32_t)0xEEFEFFFE;\r
-\r
-  /*!< Reset HSEBYP bit */\r
-  RCC->CR &= (uint32_t)0xFFFBFFFF;\r
-\r
-  /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */\r
-  RCC->CFGR &= (uint32_t)0xFF02FFFF;\r
-\r
-  /*!< Disable all interrupts */\r
-  RCC->CIR = 0x00000000;\r
-    \r
-  /* Configure the System clock frequency, AHB/APBx prescalers and Flash settings */\r
-  SetSysClock();\r
-\r
-#ifdef VECT_TAB_SRAM\r
-  SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */\r
-#else\r
-  SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */\r
-#endif\r
-}\r
-\r
-/**\r
-  * @brief  Update SystemCoreClock according to Clock Register Values\r
-  * @note   - The system frequency computed by this function is not the real \r
-  *           frequency in the chip. It is calculated based on the predefined \r
-  *           constant and the selected clock source:\r
-  *             \r
-  *           - If SYSCLK source is MSI, SystemCoreClock will contain the MSI \r
-  *             value as defined by the MSI range.\r
-  *                                   \r
-  *           - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)\r
-  *                                              \r
-  *           - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)\r
-  *                          \r
-  *           - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) \r
-  *             or HSI_VALUE(*) multiplied/divided by the PLL factors.\r
-  *         \r
-  *         (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value\r
-  *             16 MHz) but the real value may vary depending on the variations\r
-  *             in voltage and temperature.   \r
-  *    \r
-  *         (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value\r
-  *              8 MHz), user has to ensure that HSE_VALUE is same as the real\r
-  *              frequency of the crystal used. Otherwise, this function may\r
-  *              have wrong result.\r
-  *                \r
-  *         - The result of this function could be not correct when using fractional\r
-  *           value for HSE crystal.  \r
-  * @param  None\r
-  * @retval None\r
-  */\r
-void SystemCoreClockUpdate (void)\r
-{\r
-  uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0;\r
-\r
-  /* Get SYSCLK source -------------------------------------------------------*/\r
-  tmp = RCC->CFGR & RCC_CFGR_SWS;\r
-  \r
-  switch (tmp)\r
-  {\r
-    case 0x00:  /* MSI used as system clock */\r
-      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;\r
-      SystemCoreClock = (32768 * (1 << (msirange + 1)));\r
-      break;\r
-    case 0x04:  /* HSI used as system clock */\r
-      SystemCoreClock = HSI_VALUE;\r
-      break;\r
-    case 0x08:  /* HSE used as system clock */\r
-      SystemCoreClock = HSE_VALUE;\r
-      break;\r
-    case 0x0C:  /* PLL used as system clock */\r
-      /* Get PLL clock source and multiplication factor ----------------------*/\r
-      pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;\r
-      plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;\r
-      pllmul = PLLMulTable[(pllmul >> 18)];\r
-      plldiv = (plldiv >> 22) + 1;\r
-      \r
-      pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;\r
-\r
-      if (pllsource == 0x00)\r
-      {\r
-        /* HSI oscillator clock selected as PLL clock entry */\r
-        SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);\r
-      }\r
-      else\r
-      {\r
-        /* HSE selected as PLL clock entry */\r
-        SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);\r
-      }\r
-      break;\r
-    default: /* MSI used as system clock */\r
-      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;\r
-      SystemCoreClock = (32768 * (1 << (msirange + 1)));\r
-      break;\r
-  }\r
-  /* Compute HCLK clock frequency --------------------------------------------*/\r
-  /* Get HCLK prescaler */\r
-  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];\r
-  /* HCLK clock frequency */\r
-  SystemCoreClock >>= tmp;\r
-}\r
-\r
-/**\r
-  * @brief  Configures the System clock frequency, AHB/APBx prescalers and Flash \r
-  *         settings.\r
-  * @note   This function should be called only once the RCC clock configuration  \r
-  *         is reset to the default reset state (done in SystemInit() function).             \r
-  * @param  None\r
-  * @retval None\r
-  */\r
-static void SetSysClock(void)\r
-{\r
-  __IO uint32_t StartUpCounter = 0, HSIStatus = 0;\r
-  \r
-  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/\r
-  /* Enable HSI */\r
-  RCC->CR |= ((uint32_t)RCC_CR_HSION);\r
\r
-  /* Wait till HSI is ready and if Time out is reached exit */\r
-  do\r
-  {\r
-    HSIStatus = RCC->CR & RCC_CR_HSIRDY;\r
-  } while((HSIStatus == 0) && (StartUpCounter != HSI_STARTUP_TIMEOUT));\r
-\r
-  if ((RCC->CR & RCC_CR_HSIRDY) != RESET)\r
-  {\r
-    HSIStatus = (uint32_t)0x01;\r
-  }\r
-  else\r
-  {\r
-    HSIStatus = (uint32_t)0x00;\r
-  }\r
-    \r
-  if (HSIStatus == (uint32_t)0x01)\r
-  {\r
-    /* Flash 0 wait state */\r
-    FLASH->ACR &= ~FLASH_ACR_LATENCY;\r
-    \r
-    /* Disable Prefetch Buffer */\r
-    FLASH->ACR &= ~FLASH_ACR_PRFTEN;\r
-\r
-    /* Disable 64-bit access */\r
-    FLASH->ACR &= ~FLASH_ACR_ACC64;\r
-    \r
-\r
-    /* Power enable */\r
-    RCC->APB1ENR |= RCC_APB1ENR_PWREN;\r
-  \r
-    /* Select the Voltage Range 1 (1.8 V) */\r
-    PWR->CR = PWR_CR_VOS_0;\r
-  \r
-  \r
-    /* Wait Until the Voltage Regulator is ready */\r
-    while((PWR->CSR & PWR_CSR_VOSF) != RESET)\r
-    {\r
-    }\r
-      \r
-    /* HCLK = SYSCLK /1*/\r
-    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;\r
-    /* PCLK2 = HCLK /1*/\r
-    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;\r
-    \r
-    /* PCLK1 = HCLK /1*/\r
-    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;\r
-    \r
-    /* Select HSI as system clock source */\r
-    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));\r
-    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSI;\r
-\r
-    /* Wait till HSI is used as system clock source */\r
-    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_HSI)\r
-    {\r
-    }\r
-  }\r
-  else\r
-  {\r
-    /* If HSI fails to start-up, the application will have wrong clock\r
-       configuration. User can add here some code to deal with this error */\r
-  }\r
-}\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/**\r
-  * @}\r
-  */\r
-\r
-/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/\r