From: Karl Palsson Date: Mon, 7 Nov 2011 22:56:15 +0000 (+0000) Subject: Rename board specific demos as appropriate X-Git-Url: https://git.gag.com/?a=commitdiff_plain;h=d69cad884996b01fb993b3df16c1050adaca5daa;p=fw%2Fstlink Rename board specific demos as appropriate --- diff --git a/example/32l_dac/Makefile b/example/32l_dac/Makefile new file mode 100644 index 0000000..84db69e --- /dev/null +++ b/example/32l_dac/Makefile @@ -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 index 0000000..d93a184 --- /dev/null +++ b/example/32l_dac/discover_board.h @@ -0,0 +1,61 @@ + /** + ****************************************************************************** + * @file discover_board.h + * @author Microcontroller Division + * @version V1.0.2 + * @date September-2011 + * @brief Input/Output defines + ****************************************************************************** + * @copy + * + * 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. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ + +#ifndef __DISCOVER_BOARD_H +#define __DISCOVER_BOARD_H + +/* Includes ------------------------------------------------------------------*/ +/* #include "stm32l1xx.h" */ + +#define bool _Bool +#define FALSE 0 +#define TRUE !FALSE + +/* MACROs for SET, RESET or TOGGLE Output port */ + +#define GPIO_HIGH(a,b) a->BSRRL = b +#define GPIO_LOW(a,b) a->BSRRH = b +#define GPIO_TOGGLE(a,b) a->ODR ^= b + +#define USERBUTTON_GPIO_PORT GPIOA +#define USERBUTTON_GPIO_PIN GPIO_Pin_0 +#define USERBUTTON_GPIO_CLK RCC_AHBPeriph_GPIOA + +#define LD_GPIO_PORT GPIOB +#define LD_GREEN_GPIO_PIN GPIO_Pin_7 +#define LD_BLUE_GPIO_PIN GPIO_Pin_6 +#define LD_GPIO_PORT_CLK RCC_AHBPeriph_GPIOB + +#define CTN_GPIO_PORT GPIOC +#define CTN_CNTEN_GPIO_PIN GPIO_Pin_13 +#define CTN_GPIO_CLK RCC_AHBPeriph_GPIOC + +#define WAKEUP_GPIO_PORT GPIOA + +#define IDD_MEASURE_PORT GPIOA +#define IDD_MEASURE GPIO_Pin_4 + + +#endif + + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/example/32l_dac/main.c b/example/32l_dac/main.c new file mode 100644 index 0000000..1f89d33 --- /dev/null +++ b/example/32l_dac/main.c @@ -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 index 0000000..9a8389c --- /dev/null +++ b/example/32l_dac/startup_stm32l1xx_md.s @@ -0,0 +1,365 @@ +/** + ****************************************************************************** + * @file startup_stm32l1xx_md.s + * @author MCD Application Team + * @version V1.0.0 + * @date 31-December-2010 + * @brief STM32L1xx Ultra Low Power Medium-density Devices vector table for + * RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @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. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ ******************************************************************************* + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ +/* let main do the system initialization */ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/******************************************************************************* +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_STAMP_IRQHandler + .word RTC_WKUP_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word USB_HP_IRQHandler + .word USB_LP_IRQHandler + .word DAC_IRQHandler + .word COMP_IRQHandler + .word EXTI9_5_IRQHandler + .word LCD_IRQHandler + .word TIM9_IRQHandler + .word TIM10_IRQHandler + .word TIM11_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTC_Alarm_IRQHandler + .word USB_FS_WKUP_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32L15x ULtra Low Power Medium-density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_STAMP_IRQHandler + .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak USB_HP_IRQHandler + .thumb_set USB_HP_IRQHandler,Default_Handler + + .weak USB_LP_IRQHandler + .thumb_set USB_LP_IRQHandler,Default_Handler + + .weak DAC_IRQHandler + .thumb_set DAC_IRQHandler,Default_Handler + + .weak COMP_IRQHandler + .thumb_set COMP_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak LCD_IRQHandler + .thumb_set LCD_IRQHandler,Default_Handler + + .weak TIM9_IRQHandler + .thumb_set TIM9_IRQHandler,Default_Handler + + .weak TIM10_IRQHandler + .thumb_set TIM10_IRQHandler,Default_Handler + + .weak TIM11_IRQHandler + .thumb_set TIM11_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak USB_FS_WKUP_IRQHandler + .thumb_set USB_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************** (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE***/ + diff --git a/example/32l_dac/stm32_flash.ld b/example/32l_dac/stm32_flash.ld new file mode 100644 index 0000000..146b16e --- /dev/null +++ b/example/32l_dac/stm32_flash.ld @@ -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 “as is,” 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 index 0000000..6deab32 --- /dev/null +++ b/example/32l_dac/system_stm32l1xx.c @@ -0,0 +1,367 @@ +/** + ****************************************************************************** + * @file system_stm32l1xx.c + * @author MCD Application Team + * @version V1.0.0 + * @date 2-June-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32L1xx Ultra + * Low Medium-density devices, and is generated by the clock configuration + * tool "STM32L1xx_Clock_Configuration_V1.0.0.xls". + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32l1xx_md.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the MSI (2.1 MHz Range) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32l1xx_md.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and MSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define + * in "stm32l1xx.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + * System Clock Configuration + *============================================================================= + * System clock source | HSI + *----------------------------------------------------------------------------- + * SYSCLK | 16000000 Hz + *----------------------------------------------------------------------------- + * HCLK | 16000000 Hz + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 1 + *----------------------------------------------------------------------------- + * HSE Frequency | 8000000 Hz + *----------------------------------------------------------------------------- + * PLL DIV | Not Used + *----------------------------------------------------------------------------- + * PLL MUL | Not Used + *----------------------------------------------------------------------------- + * VDD | 3.3 V + *----------------------------------------------------------------------------- + * Vcore | 1.8 V (Range 1) + *----------------------------------------------------------------------------- + * Flash Latency | 0 WS + *----------------------------------------------------------------------------- + * Require 48MHz for USB clock | Disabled + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @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. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32l1xx_system + * @{ + */ + +/** @addtogroup STM32L1xx_System_Private_Includes + * @{ + */ + +#include "stm32l1xx.h" + +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_Defines + * @{ + */ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_Variables + * @{ + */ +uint32_t SystemCoreClock = 16000000; +__I uint8_t PLLMulTable[9] = {3, 4, 6, 8, 12, 16, 24, 32, 48}; +__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes + * @{ + */ + +static void SetSysClock(void); + +/** + * @} + */ + +/** @addtogroup STM32L1xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system. + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemCoreClock variable. + * @param None + * @retval None + */ +void SystemInit (void) +{ + /*!< Set MSION bit */ + RCC->CR |= (uint32_t)0x00000100; + + /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */ + RCC->CFGR &= (uint32_t)0x88FFC00C; + + /*!< Reset HSION, HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xEEFEFFFE; + + /*!< Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */ + RCC->CFGR &= (uint32_t)0xFF02FFFF; + + /*!< Disable all interrupts */ + RCC->CIR = 0x00000000; + + /* Configure the System clock frequency, AHB/APBx prescalers and Flash settings */ + SetSysClock(); + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock according to Clock Register Values + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI + * value as defined by the MSI range. + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* MSI used as system clock */ + msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13; + SystemCoreClock = (32768 * (1 << (msirange + 1))); + break; + case 0x04: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x08: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x0C: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmul = RCC->CFGR & RCC_CFGR_PLLMUL; + plldiv = RCC->CFGR & RCC_CFGR_PLLDIV; + pllmul = PLLMulTable[(pllmul >> 18)]; + plldiv = (plldiv >> 22) + 1; + + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + + if (pllsource == 0x00) + { + /* HSI oscillator clock selected as PLL clock entry */ + SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv); + } + else + { + /* HSE selected as PLL clock entry */ + SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv); + } + break; + default: /* MSI used as system clock */ + msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13; + SystemCoreClock = (32768 * (1 << (msirange + 1))); + break; + } + /* Compute HCLK clock frequency --------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock frequency, AHB/APBx prescalers and Flash + * settings. + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +static void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, HSIStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSI */ + RCC->CR |= ((uint32_t)RCC_CR_HSION); + + /* Wait till HSI is ready and if Time out is reached exit */ + do + { + HSIStatus = RCC->CR & RCC_CR_HSIRDY; + } while((HSIStatus == 0) && (StartUpCounter != HSI_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSIRDY) != RESET) + { + HSIStatus = (uint32_t)0x01; + } + else + { + HSIStatus = (uint32_t)0x00; + } + + if (HSIStatus == (uint32_t)0x01) + { + /* Flash 0 wait state */ + FLASH->ACR &= ~FLASH_ACR_LATENCY; + + /* Disable Prefetch Buffer */ + FLASH->ACR &= ~FLASH_ACR_PRFTEN; + + /* Disable 64-bit access */ + FLASH->ACR &= ~FLASH_ACR_ACC64; + + + /* Power enable */ + RCC->APB1ENR |= RCC_APB1ENR_PWREN; + + /* Select the Voltage Range 1 (1.8 V) */ + PWR->CR = PWR_CR_VOS_0; + + + /* Wait Until the Voltage Regulator is ready */ + while((PWR->CSR & PWR_CSR_VOSF) != RESET) + { + } + + /* HCLK = SYSCLK /1*/ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + /* PCLK2 = HCLK /1*/ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK /1*/ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; + + /* Select HSI as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSI; + + /* Wait till HSI is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_HSI) + { + } + } + else + { + /* If HSI fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/example/dac/Makefile b/example/dac/Makefile deleted file mode 100644 index 84db69e..0000000 --- a/example/dac/Makefile +++ /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 index d93a184..0000000 --- a/example/dac/discover_board.h +++ /dev/null @@ -1,61 +0,0 @@ - /** - ****************************************************************************** - * @file discover_board.h - * @author Microcontroller Division - * @version V1.0.2 - * @date September-2011 - * @brief Input/Output defines - ****************************************************************************** - * @copy - * - * 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. - * - *

© COPYRIGHT 2011 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ - -#ifndef __DISCOVER_BOARD_H -#define __DISCOVER_BOARD_H - -/* Includes ------------------------------------------------------------------*/ -/* #include "stm32l1xx.h" */ - -#define bool _Bool -#define FALSE 0 -#define TRUE !FALSE - -/* MACROs for SET, RESET or TOGGLE Output port */ - -#define GPIO_HIGH(a,b) a->BSRRL = b -#define GPIO_LOW(a,b) a->BSRRH = b -#define GPIO_TOGGLE(a,b) a->ODR ^= b - -#define USERBUTTON_GPIO_PORT GPIOA -#define USERBUTTON_GPIO_PIN GPIO_Pin_0 -#define USERBUTTON_GPIO_CLK RCC_AHBPeriph_GPIOA - -#define LD_GPIO_PORT GPIOB -#define LD_GREEN_GPIO_PIN GPIO_Pin_7 -#define LD_BLUE_GPIO_PIN GPIO_Pin_6 -#define LD_GPIO_PORT_CLK RCC_AHBPeriph_GPIOB - -#define CTN_GPIO_PORT GPIOC -#define CTN_CNTEN_GPIO_PIN GPIO_Pin_13 -#define CTN_GPIO_CLK RCC_AHBPeriph_GPIOC - -#define WAKEUP_GPIO_PORT GPIOA - -#define IDD_MEASURE_PORT GPIOA -#define IDD_MEASURE GPIO_Pin_4 - - -#endif - - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/example/dac/main.c b/example/dac/main.c deleted file mode 100644 index 1f89d33..0000000 --- a/example/dac/main.c +++ /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 index 9a8389c..0000000 --- a/example/dac/startup_stm32l1xx_md.s +++ /dev/null @@ -1,365 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32l1xx_md.s - * @author MCD Application Team - * @version V1.0.0 - * @date 31-December-2010 - * @brief STM32L1xx Ultra Low Power Medium-density Devices vector table for - * RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @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. - * - *

© COPYRIGHT 2010 STMicroelectronics

- ******************************************************************************* - */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the clock system intitialization function.*/ -/* let main do the system initialization */ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/******************************************************************************* -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_STAMP_IRQHandler - .word RTC_WKUP_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_IRQHandler - .word USB_HP_IRQHandler - .word USB_LP_IRQHandler - .word DAC_IRQHandler - .word COMP_IRQHandler - .word EXTI9_5_IRQHandler - .word LCD_IRQHandler - .word TIM9_IRQHandler - .word TIM10_IRQHandler - .word TIM11_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTC_Alarm_IRQHandler - .word USB_FS_WKUP_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32L15x ULtra Low Power Medium-density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_STAMP_IRQHandler - .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_IRQHandler - .thumb_set ADC1_IRQHandler,Default_Handler - - .weak USB_HP_IRQHandler - .thumb_set USB_HP_IRQHandler,Default_Handler - - .weak USB_LP_IRQHandler - .thumb_set USB_LP_IRQHandler,Default_Handler - - .weak DAC_IRQHandler - .thumb_set DAC_IRQHandler,Default_Handler - - .weak COMP_IRQHandler - .thumb_set COMP_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak LCD_IRQHandler - .thumb_set LCD_IRQHandler,Default_Handler - - .weak TIM9_IRQHandler - .thumb_set TIM9_IRQHandler,Default_Handler - - .weak TIM10_IRQHandler - .thumb_set TIM10_IRQHandler,Default_Handler - - .weak TIM11_IRQHandler - .thumb_set TIM11_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak USB_FS_WKUP_IRQHandler - .thumb_set USB_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - -/******************** (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE***/ - diff --git a/example/dac/stm32_flash.ld b/example/dac/stm32_flash.ld deleted file mode 100644 index 146b16e..0000000 --- a/example/dac/stm32_flash.ld +++ /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 “as is,” 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 index 6deab32..0000000 --- a/example/dac/system_stm32l1xx.c +++ /dev/null @@ -1,367 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32l1xx.c - * @author MCD Application Team - * @version V1.0.0 - * @date 2-June-2011 - * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File. - * This file contains the system clock configuration for STM32L1xx Ultra - * Low Medium-density devices, and is generated by the clock configuration - * tool "STM32L1xx_Clock_Configuration_V1.0.0.xls". - * - * 1. This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier - * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32l1xx_md.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * 2. After each device reset the MSI (2.1 MHz Range) is used as system clock source. - * Then SystemInit() function is called, in "startup_stm32l1xx_md.s" file, to - * configure the system clock before to branch to main program. - * - * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and MSI still used as system clock source. User can - * add some code to deal with this issue inside the SetSysClock() function. - * - * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define - * in "stm32l1xx.h" file. When HSE is used as system clock source, directly or - * through PLL, and you are using different crystal you have to adapt the HSE - * value to your own configuration. - * - * 5. This file configures the system clock as follows: - *============================================================================= - * System Clock Configuration - *============================================================================= - * System clock source | HSI - *----------------------------------------------------------------------------- - * SYSCLK | 16000000 Hz - *----------------------------------------------------------------------------- - * HCLK | 16000000 Hz - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 1 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 1 - *----------------------------------------------------------------------------- - * HSE Frequency | 8000000 Hz - *----------------------------------------------------------------------------- - * PLL DIV | Not Used - *----------------------------------------------------------------------------- - * PLL MUL | Not Used - *----------------------------------------------------------------------------- - * VDD | 3.3 V - *----------------------------------------------------------------------------- - * Vcore | 1.8 V (Range 1) - *----------------------------------------------------------------------------- - * Flash Latency | 0 WS - *----------------------------------------------------------------------------- - * Require 48MHz for USB clock | Disabled - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @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. - * - *

© COPYRIGHT 2010 STMicroelectronics

- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32l1xx_system - * @{ - */ - -/** @addtogroup STM32L1xx_System_Private_Includes - * @{ - */ - -#include "stm32l1xx.h" - -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_Defines - * @{ - */ -/*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ -/* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_Variables - * @{ - */ -uint32_t SystemCoreClock = 16000000; -__I uint8_t PLLMulTable[9] = {3, 4, 6, 8, 12, 16, 24, 32, 48}; -__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; - -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes - * @{ - */ - -static void SetSysClock(void); - -/** - * @} - */ - -/** @addtogroup STM32L1xx_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system. - * Initialize the Embedded Flash Interface, the PLL and update the - * SystemCoreClock variable. - * @param None - * @retval None - */ -void SystemInit (void) -{ - /*!< Set MSION bit */ - RCC->CR |= (uint32_t)0x00000100; - - /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */ - RCC->CFGR &= (uint32_t)0x88FFC00C; - - /*!< Reset HSION, HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xEEFEFFFE; - - /*!< Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */ - RCC->CFGR &= (uint32_t)0xFF02FFFF; - - /*!< Disable all interrupts */ - RCC->CIR = 0x00000000; - - /* Configure the System clock frequency, AHB/APBx prescalers and Flash settings */ - SetSysClock(); - -#ifdef VECT_TAB_SRAM - SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ -#else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ -#endif -} - -/** - * @brief Update SystemCoreClock according to Clock Register Values - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI - * value as defined by the MSI range. - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value - * 8 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * @param None - * @retval None - */ -void SystemCoreClockUpdate (void) -{ - uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0; - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & RCC_CFGR_SWS; - - switch (tmp) - { - case 0x00: /* MSI used as system clock */ - msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13; - SystemCoreClock = (32768 * (1 << (msirange + 1))); - break; - case 0x04: /* HSI used as system clock */ - SystemCoreClock = HSI_VALUE; - break; - case 0x08: /* HSE used as system clock */ - SystemCoreClock = HSE_VALUE; - break; - case 0x0C: /* PLL used as system clock */ - /* Get PLL clock source and multiplication factor ----------------------*/ - pllmul = RCC->CFGR & RCC_CFGR_PLLMUL; - plldiv = RCC->CFGR & RCC_CFGR_PLLDIV; - pllmul = PLLMulTable[(pllmul >> 18)]; - plldiv = (plldiv >> 22) + 1; - - pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; - - if (pllsource == 0x00) - { - /* HSI oscillator clock selected as PLL clock entry */ - SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv); - } - else - { - /* HSE selected as PLL clock entry */ - SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv); - } - break; - default: /* MSI used as system clock */ - msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13; - SystemCoreClock = (32768 * (1 << (msirange + 1))); - break; - } - /* Compute HCLK clock frequency --------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; - /* HCLK clock frequency */ - SystemCoreClock >>= tmp; -} - -/** - * @brief Configures the System clock frequency, AHB/APBx prescalers and Flash - * settings. - * @note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). - * @param None - * @retval None - */ -static void SetSysClock(void) -{ - __IO uint32_t StartUpCounter = 0, HSIStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSI */ - RCC->CR |= ((uint32_t)RCC_CR_HSION); - - /* Wait till HSI is ready and if Time out is reached exit */ - do - { - HSIStatus = RCC->CR & RCC_CR_HSIRDY; - } while((HSIStatus == 0) && (StartUpCounter != HSI_STARTUP_TIMEOUT)); - - if ((RCC->CR & RCC_CR_HSIRDY) != RESET) - { - HSIStatus = (uint32_t)0x01; - } - else - { - HSIStatus = (uint32_t)0x00; - } - - if (HSIStatus == (uint32_t)0x01) - { - /* Flash 0 wait state */ - FLASH->ACR &= ~FLASH_ACR_LATENCY; - - /* Disable Prefetch Buffer */ - FLASH->ACR &= ~FLASH_ACR_PRFTEN; - - /* Disable 64-bit access */ - FLASH->ACR &= ~FLASH_ACR_ACC64; - - - /* Power enable */ - RCC->APB1ENR |= RCC_APB1ENR_PWREN; - - /* Select the Voltage Range 1 (1.8 V) */ - PWR->CR = PWR_CR_VOS_0; - - - /* Wait Until the Voltage Regulator is ready */ - while((PWR->CSR & PWR_CSR_VOSF) != RESET) - { - } - - /* HCLK = SYSCLK /1*/ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - /* PCLK2 = HCLK /1*/ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK /1*/ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; - - /* Select HSI as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSI; - - /* Wait till HSI is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_HSI) - { - } - } - else - { - /* If HSI fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/